ROS Widgets

jupyros.ros1.pubsub.subscribe(topic, msg_type, callback)

Subscribes to a specific topic in another thread, but redirects output!

@param topic The topic @param msg_type The message type @param callback The callback

@return Jupyter output widget

jupyros.ros1.ros_widgets.action_client(action_name, action_msg, goal_msg, callbacks=None)

Create a form widget for message type action_msg. This function analyzes the fields of action_msg and creates an appropriate widget. An action client is automatically created which sends a goal to the action server given as action_name. This allows pressing the “Send Goal” button to send the message to ROS.

@param action_name The namespace in which to access the action @param action_msg The action message type @param goal_msg The goal message type @param callbacks A dictionary of callback function handles with

optional keys: done_cb, active_cb and feedback_cb

@return jupyter widget for display

jupyros.ros1.ros_widgets.add_widgets(msg_instance, widget_dict, widget_list, prefix='')

Adds widgets.

@param msg_type The message type @param widget_dict The form list @param widget_list The widget list

@return widget_dict and widget_list

jupyros.ros1.ros_widgets.bag_player(bagfile='')

Create a form widget for playing ROS bags. This function takes the bag file path, extracts the bag summary and play the bag with the given arguments.

@param bagfile The ROS bag file path

@return jupyter widget for display

jupyros.ros1.ros_widgets.client(*args, **kwargs)

Deprecated client for ROS services. Use service_client() instead.

jupyros.ros1.ros_widgets.publish(topic, msg_type)

Create a form widget for message type msg_type. This function analyzes the fields of msg_type and creates an appropriate widget. A publisher is automatically created which publishes to the topic given as topic parameter. This allows pressing the “Send Message” button to send the message to ROS.

@param msg_type The message type @param topic The topic name to publish to

@return jupyter widget for display

jupyros.ros1.ros_widgets.service_client(srv_name, srv_type)

Create a form widget for message type srv_type. This function analyzes the fields of srv_type and creates an appropriate widget.

@param srv_type The service message type @param srv_name The service name to call

@return jupyter widget for display

class jupyros.ros1.ros3d.DepthCloud(**kwargs: Any)

Display a Depth Cloud for a RGB-D cloud (needs infrastructure on the server side.)

class jupyros.ros1.ros3d.GridModel(**kwargs: Any)

A simple GridModel

Displays a 3D grid.

Parameters:
  • cell_size (Float) – Size of the cells in meters

  • color (Unicode) – Color of the grid lines (e.g. a hex specifier #FF0000)

  • num_cells (Int) – Number of cells in length, and width (default: 2)0

class jupyros.ros1.ros3d.InteractiveMarker(**kwargs: Any)

Interactive Marker Widget

Displays an interactive marker in the Viewer.

Parameters:
  • ros (ROSConnection instance) – Instance of the ROS Connection that should be used

  • tf_client (TFClient instance) – Instance of the TF Client that should be used

  • topic (Unicode) – The topic to subscribe to (default: /basic_controls)

  • menu_font_size (Unicode) – Menu font size (default: '0.8em')

class jupyros.ros1.ros3d.LaserScan(**kwargs: Any)

Displays a LaserScan message

Parameters:
  • ros (ROSConnection instance) – Instance of the ROS Connection that should be used

  • tf_client (TFClient instance) – Instance of the TF Client that should be used

  • topic (Unicode) – Name of the topic (default: /scan)

  • point_ratio (Float) – Ratio of points to send to the frontend (default: 1.0)

  • message_ratio (Float) – Ratio of messages to send to the frontend (default: 1.0)

  • max_points (Int) – Maximum number of points to display (default: 200000)

  • color_source (Unicode) – Source field for the color information (default: ‘intensities’)

  • color_map (Unicode) – Color map function (default: ‘’)

  • point_size (Float) – Point size (default: 0.05)

  • static_color (Unicode) – Hex string of the color for visualization (default: "#FF0000")

class jupyros.ros1.ros3d.Marker(**kwargs: Any)

Displays a Marker message

Parameters:
  • ros (ROSConnection instance) – Instance of the ROS Connection that should be used

  • tf_client (TFClient instance) – Instance of the TF Client that should be used

  • topic (Unicode) – Name of the topic (default: /pose_array)

  • path (Unicode) – Marker path (default: /)

  • lifetime (Float) – Lifetime of marker in seconds, 0 for infinity (default: 0.0)

class jupyros.ros1.ros3d.MarkerArrayClient(**kwargs: Any)

A client that listens to changes in a MarkerArray and triggers the update of a visualization.

Parameters:
  • ros (ROSConnection instance) – Instance of the ROS Connection that should be used

  • tf_client (TFClient instance) – Instance of the TF Client that should be used

  • topic (Unicode) – Name of the topic (default: /marker_array)

  • path (Unicode) – The base path to any meshes that will be loaded (default: '/')

class jupyros.ros1.ros3d.OccupancyGrid(**kwargs: Any)

Displays an Occupancy Grid

Parameters:
  • ros (ROSConnection instance) – Instance of the ROS Connection that should be used

  • tf_client (TFClient instance) – Instance of the TF Client that should be used

  • topic (Unicode) – The topic to subscribe to (default: /basic_controls)

  • continuous (Book) – Wether the occupancy grid should continously update (default: False)

  • compression (Unicode) – Compression mechanism (default: ‘cbor’)

  • color (Unicode) – Color of the grid lines (e.g. a hex specifier #FFFFFF)

  • opacity (Float) – Opacity of the occupancy grid (default: 1.0)

class jupyros.ros1.ros3d.Path(**kwargs: Any)

Displays a Path message

Parameters:
  • ros (ROSConnection instance) – Instance of the ROS Connection that should be used

  • tf_client (TFClient instance) – Instance of the TF Client that should be used

  • topic (Unicode) – Name of the topic (default: /path)

  • color (Unicode) – Hex string of the color for visualization (default: "#CC00FF")

class jupyros.ros1.ros3d.PointCloud(**kwargs: Any)

Displays a PointCloud message

Parameters:
  • ros (ROSConnection instance) – Instance of the ROS Connection that should be used

  • tf_client (TFClient instance) – Instance of the TF Client that should be used

  • topic (Unicode) – Name of the topic (default: /point_cloud)

  • point_ratio (Float) – Ratio of points to send to the frontend (default: 1.0)

  • message_ratio (Float) – Ratio of messages to send to the frontend (default: 1.0)

  • max_points (Int) – Maximum number of points to display (default: 200000)

  • point_size (Float) – Point size (default: 0.05)

  • static_color (Unicode) – Hex string of the color for visualization (default: "#FF0000")

class jupyros.ros1.ros3d.Polygon(**kwargs: Any)

Displays a Polygon message

Parameters:
  • ros (ROSConnection instance) – Instance of the ROS Connection that should be used

  • tf_client (TFClient instance) – Instance of the TF Client that should be used

  • topic (Unicode) – Name of the topic (default: /polygon)

  • color (Unicode) – Hex string of the color for visualization (default: "#CC00FF")

class jupyros.ros1.ros3d.Pose(**kwargs: Any)

Displays a Pose message

Parameters:
  • ros (ROSConnection instance) – Instance of the ROS Connection that should be used

  • tf_client (TFClient instance) – Instance of the TF Client that should be used

  • topic (Unicode) – Name of the topic (default: /pose)

  • color (Unicode) – Hex string of the color for visualization (default: "#CC00FF")

  • length (Float) – Length of pose arrows (default: 1m)

class jupyros.ros1.ros3d.PoseArray(**kwargs: Any)

Displays a PoseArray message

Parameters:
  • ros (ROSConnection instance) – Instance of the ROS Connection that should be used

  • tf_client (TFClient instance) – Instance of the TF Client that should be used

  • topic (Unicode) – Name of the topic (default: /pose_array)

  • color (Unicode) – Hex string of the color for visualization (default: "#CC00FF")

  • length (Float) – Length of pose arrows (default: 1m)

class jupyros.ros1.ros3d.ROSConnection(**kwargs: Any)

Base ROS Connection

The ROS Connection widget has the parameters with the websocket endpoint to communicate with the rosbridge server.

Parameters:

url (Unicode) – URL endpoint of the websocket. Defaults to ws://{hostname}:9090 where {hostname} is replaced by the current hostname at runtime (e.g. localhost). You can override the default value by setting the JUPYTER_WEBSOCKET_URL environment variable.

class jupyros.ros1.ros3d.SceneNode(**kwargs: Any)

Scene Node (to be used in conjunction with DepthCloud)

class jupyros.ros1.ros3d.TFClient(**kwargs: Any)

Base TF Client

The TFClient keeps track of TF frames.

Parameters:
  • angular_treshold (Float) – The angular threshold for the TF republisher (default: 0.01)

  • translational_treshold (Float) – The translation threshold for the TF republisher (default: 0.01)

  • rate (Float) – Update and publish rate for the TF republisher (default: 10.0)

  • fixed_frame (Unicode) – Fixed base frame for TF tree (default: ‘’)

class jupyros.ros1.ros3d.URDFModel(**kwargs: Any)

A URDFModel (Robot model)

Displays a 3D robot model.

Parameters:
  • ros (ROSConnection instance) – Instance of the ROS Connection that should be used

  • tf_client (TFClient instance) – Instance of the TF Client that should be used

  • url (Unicode) – URL from which to fetch the _assets_ (mesh and texture files). This can be either the jupyter-ros server extension (in this case one should use “http://{hostname}:{port}/rospkg/”) or another server / URL where the mesh files can be downloaded (default: “http://{hostname}:3000”)

class jupyros.ros1.ros3d.Viewer(**kwargs: Any)

Viewer class

This is the class that represents the actual 3D viewer widget. The viewer is derived from the ipywidgets.DOMWidget and therefore also implements the layout attribute which can be used to modify the CSS layout of the viewer.

Parameters:
  • background_color (Unicode) – Background color of the viewer (default: '#FFFFFF')

  • alpha (Float) – The alpha value of the background

  • objects (List of ROS3D widget instances) – Objects to render in the viewer (e.g. Marker, PointCloud, …)

ROS2 Widgets

Coming soon!