Studio Live

class Studio

Helper class to connect and visualize trajectories and events in Jacobi Studio.

The Studio class provides functionality to connect to Jacobi Studio via a WebSocket, and to visualize trajectories and events. It manages the connection, handles incoming and outgoing messages, and allows the user to create and execute actions within Jacobi Studio.

Public Functions

explicit Studio(bool auto_connect = true, double timeout = 5.0)

Interface Jacobi Studio via code. Connects to Jacobi Studio automatically - please make sure to enable the Studio Live feature in the Jacobi Studio settings.

Parameters:
  • auto_connect – Whether to connect to Studio Live automatically.

  • timeout – The timeout for connecting to Studio Live.

inline void register_message_callback(const MessageCallback &callback)

Setup a callback for incoming message.

bool reconnect(double timeout = 5.0)

Reconnect to Studio Live.

Parameters:

timeout – The timeout for reconnecting to Studio Live.

Returns:

Whether the reconnection was successful.

bool is_connected() const

Whether the library is connected to Studio Live.

Returns:

Whether the library is connected to Studio Live.

bool run_action(const Action &action) const

Run the given action in Jacobi Studio.

Parameters:

action – The action to be run.

Returns:

Was the action successfully sent to Studio?

nlohmann::json get_from_action(const Action &action, const std::string &response_key)

Get an answer from Jacobi Studio.

Parameters:

action – The action to receive an answer for.

bool run_trajectory(const Trajectory &trajectory, const Events &events = {}, bool loop_forever = false, const std::shared_ptr<Robot> robot = nullptr) const

Runs a trajectory for the given robot (or the last active robot) in Jacobi Studio, alongside the events at the specified timings. Optionally, the visualization can be looped.

Parameters:
  • trajectory – The trajectory to be run.

  • events – The events to be run at the specified timings.

  • loop_forever – Whether to loop the visualization forever.

  • robot – Optional robot to run the trajectory for.

bool run_trajectories(const std::vector<std::pair<Trajectory, std::shared_ptr<Robot>>> &trajectories, const Events &events = {}, bool loop_forever = false) const

Runs multiple trajectories for different robots in parallel, alongside the events at the specified timings. Optionally, the visualization can be looped.

Parameters:
  • trajectories – Pairs of trajectories per robot to be run.

  • events – The events to be run at the specified timings.

  • loop_forever – Whether to loop the visualization forever.

bool run_events(const Events &events) const

Run the events at the specified timings in Jacobi Studio.

Parameters:

events – The events to be run at the specified timings.

inline bool set_joint_position(const Config &joint_position, const std::shared_ptr<Robot> robot = nullptr) const

Sets the joint position of the given robot, or the last active robot instead.

Parameters:
  • joint_position – The desired joint position.

  • robot – Optional robot to set the joint position for.

inline bool set_item(const std::optional<Obstacle> &obstacle, const std::shared_ptr<Robot> robot = nullptr) const

Sets the item obstacle of the given robot, or the last active robot instead.

Parameters:
  • obstacle – Optional obstacle to be set.

  • robot – Optional robot associated with the obstacle.

inline bool set_material(const std::string &material, const std::shared_ptr<Robot> robot = nullptr) const

Sets the material of the given robot, or the last active robot instead.

Parameters:
  • material – The material to be set.

  • robot – Optional robot associated with the material.

inline bool add_robot(const std::shared_ptr<Robot> &robot) const

Adds the given robot to the environment.

Parameters:

robot – The robot to be added.

inline bool add_robot_path(const std::vector<std::vector<double>> &points, const std::shared_ptr<Robot> robot = nullptr, const std::string &name = "", const std::string &color = "", float stroke = -1.0, float arrow_size = 1.0) const

Adds a visualization of a path for the given robot.

Parameters:
  • points – The points defining the path.

  • robot – Optional robot associated with the path.

  • name – Optional name for the path.

  • color – Optional color for the path visualization.

  • stroke – Optional stroke width for the path visualization.

  • arrow_size – Optional size of arrow for end of path

inline bool remove_robot_path(const std::shared_ptr<Robot> robot, const std::string &name) const

Removes a named visualization of a path for the given robot.

Parameters:
  • robot – The robot associated with the path.

  • name – The name of the path to be removed.

inline bool add_obstacle(const Obstacle &obstacle) const

Adds the given obstacle to the environment.

Parameters:

obstacle – The obstacle to be added.

inline bool add_waypoint(const Point &point) const

Adds the given Cartesian waypoint to the environment.

Parameters:

point – The Cartesian waypoint to be added.

inline bool update_obstacle(const Obstacle &obstacle) const

Updates the obstacle with the same name.

Parameters:

obstacle – The obstacle to be updated.

inline bool remove_obstacle(const Obstacle &obstacle) const

Removes the given obstacle (by name) from the environment.

Parameters:

obstacle – The obstacle to be removed.

inline bool set_io_signal(const std::string &name, std::variant<int, float> value, const std::shared_ptr<Robot> robot = nullptr) const

Sets an I/O signal of the given robot, or the last active robot instead.

Parameters:
  • name – The name of the I/O signal.

  • value – The value to be set for the I/O signal.

  • robot – Optional robot associated with the I/O signal.

inline bool set_camera_image_encoded(const std::string &image, const std::shared_ptr<Camera> camera = nullptr) const

Sets an image for a camera encoded as a string.

Parameters:
  • image – The encoded image to be set.

  • camera – Optional camera associated with the image.

inline bool set_camera_depth_map(const std::vector<std::vector<double>> &depths, float x, float y, const std::shared_ptr<Camera> camera = nullptr) const

Sets the depth map visualization of a camera.

Parameters:
  • depths – The depth map data.

  • x – The x-coordinate for the depth map.

  • y – The y-coordinate for the depth map.

  • camera – Optional camera associated with the depth map.

inline bool set_camera_point_cloud(const std::vector<double> &points, const std::shared_ptr<Camera> camera = nullptr) const

Sets the point cloud visualization of a camera.

Parameters:
  • points – The point cloud data.

  • camera – Optional camera associated with the point cloud.

inline bool add_camera(const std::shared_ptr<Camera> camera) const

Adds a camera in Jacobi Studio.

Parameters:

camera – The camera to be added.

inline bool update_camera(const std::shared_ptr<Camera> camera) const

Updates the camera with the same name in Jacobi Studio.

Parameters:

camera – The camera to be updated.

inline bool remove_camera(const std::shared_ptr<Camera> camera) const

Removes a camera in Jacobi Studio.

Parameters:

camera – The camera to be removed.

inline bool reset() const

Resets the environment to the state before a trajectory or events were run. In particular, it removes all obstacles there were added dynamically.

inline Config get_joint_position(const std::shared_ptr<Robot> robot = nullptr)

Get the joint position of a robot.

Parameters:

robot – Optional robot to get the joint position for.

Returns:

The joint position of the robot.

inline std::string get_camera_image_encoded(CameraStream stream, const std::shared_ptr<Camera> camera = nullptr)

Get an image from a camera encoded as a string.

Parameters:
  • stream – The type of camera stream to get.

  • camera – Optional camera to get the image from.

Returns:

The encoded image from the camera.

Public Members

std::string host = {"localhost"}

Host of the websocket connection.

int port = {8768}

Port of the websocket connection.

double speedup = {1.0}

A factor to speed up or slow down running trajectories or events.

class Action

An action that can be performed in Jacobi Studio.

The Action class represents an action in Jacobi Studio, such as setting a robot’s joint position, adding an obstacle, or manipulating the environment. An action can contain multiple commands, allowing for complex interactions in Studio.

struct Events : public std::multimap<double, Action>

A container that maps a specific timing to one or multiple actions. The static methods of this class do not change the visualization in Jacobi Studio immediately, but only return an action that can be executed later (e.g. alongside a trajectory).

The Events struct allows for scheduling actions in Jacobi Studio at specific times. Static methods are provided to create various actions, which can be executed later.

Public Static Functions

static inline Action set_joint_position(const Config &joint_position, const std::shared_ptr<Robot> robot = nullptr)

Returns an action that sets the joint position of the given robot, or the last active robot instead.

Parameters:
  • joint_position – The desired joint position.

  • robot – Optional robot to set the joint position for.

Returns:

The action to set the joint position.

static inline Action set_item(const std::optional<Obstacle> &obstacle, const std::shared_ptr<Robot> robot = nullptr)

Returns an action that sets the item obstacle of the given robot, or the last active robot instead.

Parameters:
  • obstacle – Optional obstacle to be set.

  • robot – Optional robot associated with the obstacle.

Returns:

The action to set the item obstacle.

static inline Action set_material(const std::string &material, const std::shared_ptr<Robot> robot = nullptr)

Returns an action that sets the material of the given robot, or the last active robot instead.

Parameters:
  • material – The material to be set.

  • robot – Optional robot associated with the material.

Returns:

The action to set the material.

static inline Action add_robot(const std::shared_ptr<Robot> &robot)

Returns an action that adds the given robot to the environment.

Parameters:

robot – The robot to be added.

Returns:

The action to add the robot.

static inline Action add_robot_path(const std::vector<std::vector<double>> &points, const std::shared_ptr<Robot> robot = nullptr, const std::string &name = "", const std::string &color = "", float stroke = -1.0, float arrow_size = 1.0)

Returns an action that adds a visualization of a path for the given robot.

Parameters:
  • points – The points defining the path.

  • robot – Optional robot associated with the path.

  • name – Optional name for the path.

  • color – Optional color for the path visualization.

  • stroke – Optional stroke width for the path visualization.

  • arrow_size – Optional size of arrow for end of path

Returns:

The action to add the robot path visualization.

static inline Action remove_robot_path(const std::shared_ptr<Robot> robot, const std::string &name)

Returns an action that removes a visualization of a named path for the given robot.

Parameters:
  • robot – The robot associated with the path.

  • name – The name of the path to be removed.

Returns:

The action to remove the robot path visualization.

static inline Action add_obstacle(const Obstacle &obstacle)

Returns an action that adds the given obstacle to the environment.

Parameters:

obstacle – The obstacle to be added.

Returns:

The action to add the obstacle.

static inline Action add_waypoint(const Point &point)

Returns an action that adds the given Cartesian waypoint to the environment.

Parameters:

point – The Cartesian waypoint to be added.

Returns:

The action to add the Cartesian waypoint.

static inline Action update_obstacle(const Obstacle &obstacle)

Returns an action that updates the obstacle with the same name.

Parameters:

obstacle – The obstacle to be updated.

Returns:

The action to update the obstacle.

static inline Action remove_obstacle(const Obstacle &obstacle)

Returns an action that removes the given obstacle (by name) from the environment.

Parameters:

obstacle – The obstacle to be removed.

Returns:

The action to remove the obstacle.

static inline Action set_io_signal(const std::string &name, std::variant<int, float> value, const std::shared_ptr<Robot> robot = nullptr)

Returns an action that sets an I/O signal of the given robot, or the last active robot instead.

Parameters:
  • name – The name of the I/O signal.

  • value – The value to be set for the I/O signal.

  • robot – Optional robot associated with the I/O signal.

Returns:

The action to set the I/O signal.

static inline Action set_camera_image_encoded(const std::string &image, const std::shared_ptr<Camera> camera = nullptr)

Returns an action that sets an image for a camera encoded as a string.

Parameters:
  • image – The encoded image to be set.

  • camera – Optional camera associated with the image.

Returns:

The action to set the camera image.

static inline Action set_camera_depth_map(const std::vector<std::vector<double>> &depths, float x, float y, const std::shared_ptr<Camera> camera = nullptr)

Returns an action that sets the depth map visualization of a camera.

Parameters:
  • depths – The depth map data.

  • x – The x-coordinate for the depth map.

  • y – The y-coordinate for the depth map.

  • camera – Optional camera associated with the depth map.

Returns:

The action to set the camera depth map.

static inline Action set_camera_point_cloud(const std::vector<double> &points, const std::shared_ptr<Camera> camera = nullptr)

Returns an action that sets the point cloud visualization of a camera.

Parameters:
  • points – The point cloud data.

  • camera – Optional camera associated with the point cloud.

Returns:

The action to set the camera point cloud.

static inline Action add_camera(const std::shared_ptr<Camera> camera)

Returns an action that adds a camera.

Parameters:

camera – The camera to be added.

Returns:

The action to add the camera.

static inline Action update_camera(const std::shared_ptr<Camera> camera)

Returns an action that updates a camera with the same name.

Parameters:

camera – The camera to be updated.

Returns:

The action to update the camera.

static inline Action remove_camera(const std::shared_ptr<Camera> camera)

Returns an action that removes a camera.

Parameters:

camera – The camera to be removed.

Returns:

The action to remove the camera.