-
Notifications
You must be signed in to change notification settings - Fork 47
User guide
This guide is for developers who want to use <ros-rviz>
in their own applications.
See Downloading and adding ros-rviz to a page.
Releases follow semantic versioning.
That is, the major version number will update for backwards-incompatible changes.
Generally, any change to the properties or methods of the main <ros-rviz>
element and any change to the structure of the config
will be considered backwards-incompatible.
This means that you can safely run bower update
if you have a bower.json
entry like: "ros-rviz": "jstnhuang/ros-rviz#^3.0.0"
.
To use <ros-rviz>
, you must run, at a minimum, a rosbridge websocket server and tf2_web_republisher.
Here is a sample launch file for these requirements:
<launch>
<include file="$(find rosbridge_server)/launch/rosbridge_websocket.launch" />
<node pkg="tf2_web_republisher" type="tf2_web_republisher" name="tf2_web_republisher" />
</launch>
Warning: if a user enters a non-existent frame ID into <ros-rviz>
, tf2_web_republisher
will publish an error message saying that frame does not exist at a high frequency, forever.
For that reason, it is a good idea to regularly check on tf2_web_republisher
and restart it if necessary.
The <ros-rviz>
is configured by its config
property, which is a JavaScript object.
The best way to figure out the format of the config
is to manually set up <ros-rviz>
and click on the "Load config" button.
The overall structure is like so:
var config = {
globalOptions: { ... },
sidebarOpened: true,
displays: [ {...}, {...}, ...]
};
-
globalOptions contains various global options. It appears at the top of the display list and cannot be removed by the user.
- background: The background color of the viewer
- colladaLoader: Either "collada" or "collada2", specifies what version of the Collada loader to use.
- colladaServer: Server that serves mesh files, as described in the "Robot model" display documentation below.
- fixedFrame: The fixed frame of the overall visualization
- url: The websocket URL to connect to
- videoServer: A ros_web_video server URL, used mainly for the depth cloud display
- sidebarOpened: True or false, whether the sidebar is opened or not
-
displays: A list of display objects. Each display object has the following structure:
- isShown: True or false, whether or not the display is hidden or shown
- name: The name of the display shown in the sidebar
- options: An object of display-specific options, documented in more detail in the displays section below
- type: The type of the display. Currently supported types are: "depthCloud", "grid", "interactiveMarkers", "markers", "markerArray", "occupancyGrid", "pointCloud2", and "urdf".
You can use the "Load config" button to view the current config and replace it with another.
There are two ways to update the config programmatically:
To update the entire config (e.g., on page load), set the config
property to a new JavaScript object of the config:
var updated_config = { ... };
var rviz = document.getElementById('rviz');
rviz.config = updated_config;
This may cause noticeable refreshes, such as meshes being reloaded, etc.
To just update part of the config, use the set
method on the element:
var rviz = document.getElementById('rviz');
rviz.set('config.displays.0.name', 'Hello world');
rviz.set('config.sidebarOpened', false);
To manipulate arrays in the config (such as to add or remove a display), use the push
or splice
methods, which behave just like the native Array methods of the same name:
var display = {
isShown: true,
name: "Grid",
options: {
cellSize: "1",
color: "#cccccc",
numCells: "10"
},
type: "grid"
};
rviz.push('config.displays', display);
rviz.splice('config.displays', 0, 1); // Delete 1 display starting from index 0.
Each display is documented below.
Sample config:
{
isShown: true,
name: "Depth cloud",
options: {
topic: "depthcloud_encoded",
frameId: "/head_camera_rgb_optical_frame"
},
type: "depthCloud"
}
Before you can run a depth cloud, you must run a depthcloud_encoder node. See the ros3djs Point Cloud Streaming from a Kinect tutorial.
This display assumes that ros_web_video is running on config.globalOptions.videoServer
, which is http://WINDOW.LOCATION.HOSTNAME:9999
by default.
We also assume that the focal length of the camera is 525.
The tutorial above assumes that you are using a Kinect, which requires you to run the depth_image_proc/convert_metric
nodelet.
This is only needed for cameras whose drivers produce depth data with the 16UC1
encoding.
16UC1
data is interpreted as a 16-bit millimeter distance.
Other cameras may produce data with the 32FC
encoding, which is interpreted as a 32-bit floating point distance in meters.
To check if your camera needs to run the depth_image_proc/convert_metric
nodelet, run the appropriate command similar to this:
rostopic echo /camera/depth_registered/image_raw -n1 | less
Check the encoding
field.
If it is 32FC1
, you do not need to run convert_metric
.
If it is 16UC1
, you do.
Also, be careful: for some robots, this may differ in simulation versus on the real robot.
This sample launch file starts ros_web_video
on port 9999, and runs depthcloud_encoder with the given depth topic, color topic, and camera frame.
Set convert_metric
to true
or false
as described above.
<launch>
<arg name="convert_metric" doc="Set to true if the depth encoding is 16UC1, false if it is 32FC1" />
<arg name="depth_topic" default="/head_camera/depth_registered/image_raw" />
<arg name="color_topic" default="/head_camera/rgb/image_raw" />
<arg name="camera_frame" default="/head_camera_rgb_optical_frame" />
<node pkg="ros_web_video" type="ros_web_video" name="web_video_server">
<param name="port" value="9999" />
<param name="framerate" value="15" />
<param name="bitrate" value="250000" />
<param name="profile" value="best" />
</node>
<node pkg="nodelet" type="nodelet" name="convert_metric" args="standalone depth_image_proc/convert_metric" if="$(arg convert_metric)">
<remap from="image_raw" to="$(arg depth_topic)" />
<remap from="image" to="$(arg depth_topic)_float" />
</node>
<node pkg="depthcloud_encoder" type="depthcloud_encoder_node" name="depthcloud_encoder">
<param name="rgb" value="$(arg color_topic)" />
<param if="$(arg convert_metric)" name="depth" value="$(arg depth_topic)_float" />
<param unless="$(arg convert_metric)" name="depth" value="$(arg depth_topic)" />
<param name="camera_frame_id" value="$(arg camera_frame)" />
</node>
</launch>
Sample config:
{
isShown: true,
name: "Grid",
options: {
cellSize: 1,
color: "#cccccc",
numCells: 10
},
type: "grid"
}
Sample config:
{
isShown: true,
name: "Interactive markers",
options: {
topic: "/basic_controls"
},
type: "interactiveMarkers"
}
To use interactive markers, you must run an instance of interactive_marker_proxy for each interactive marker server you want to run. See the ros3djs Visualizing Interactive Markers tutorial.
Here is a sample launch file for the /basic_controls
interactive marker server:
<node pkg="interactive_marker_proxy" type="proxy" name="interactive_marker_proxy_basic_controls">
<remap from="target_frame" to="/base_link" />
<remap from="topic_ns" to="/basic_controls" />
</node>
Sample config:
{
isShown: true,
name: "Markers",
options: {
topic: "/visualization_marker"
},
type: "markers"
}
This display visualizes a visualization_msgs/Marker topic. Note that unlike the desktop version of rviz, you cannot show or hide specific namespaces of markers. If you want to display a mesh marker, you must serve the meshes as described in the "Robot model" section below.
Sample config:
{
isShown: true,
name: "Marker array",
options: {
topic: "/visualization_marker_array"
},
type: "markerArray"
}
This display visualizes a visualization_msgs/MarkerArray topic. If you want to display mesh markers, you must serve the meshes as described in the "Robot model" section below.
Sample config (note that you may see a color
option, but it is ignored):
{
isShown: true,
name: "Map",
options: {
continuous: true,
opacity: 1,
topic: "/map"
},
type: "occupancyGrid"
}
This display shows a map (nav_msgs/OccupancyGrid). You must serve the map using:
rosrun map_server map_server /path/to/map.yaml
Sample config:
{
isShown: true,
name: "Point cloud",
options: {
topic: "/cloud",
size: 0.01
},
type: "pointCloud2"
}
This display subscribes to a sensor_msgs/PointCloud2 topic. However, you should not use this display to visualize point clouds that are published at a high frequency. In its current implementation, ros3djs uses the main thread to process each point cloud, which can take a couple of seconds per point cloud. As a result, if you subscribe to a topic that publishes point clouds even as slowly as 1 Hz, the browser will be frozen and impossible to use. To reiterate: you should only use this display to show point clouds that are very small or published very occasionally.
Sample config:
{
isShown: true,
name: "Robot model",
options: {
param: "robot_description"
},
type: "urdf"
}
Loads the URDF described in the robot_description
param.
To visualize a robot model or a visualization_msgs/Marker mesh, you need to run a static file server that serves the meshes. The server must be configured to allow for cross-origin requests. A guide for doing this with the Caddy and Apache servers is here: https://github.com/hcrlab/wiki/blob/master/web_development/serving_urdf.md
Once you have a file server running, change the Global options / Collada file server URL to the base URL of your server.
By default, it is set to http://WINDOW.LOCATION.HOSTNAME:8001
.
Also note that the Robot Web Tools effort runs a file server for several robots at http://resources.robotwebtools.org, as described here.