jsk_visualization

jsk_visualization is a stack for the visualization packages which are used in JSK lab.

The code is open source, and available on github.

This repository contains following ros packages:

jsk_rviz_plugins

jsk_rviz_plugins is a package to provide original rviz plugins.

You can use these rviz plugins, panels and tools just by launching rviz.

SegmentArray

What is this?

Visualize jsk_recognition_msgs/SegmentArray.msg.

_images/segment_array.png

Sample

roslaunch jsk_rviz_plugins segment_array_sample.launch

BoundingBox

What is this?

Visualize jsk_recognition_msgs/BoundingBox.msg.

_images/bounding_box.png

BoundingBoxArray

What is this?

Visualize jsk_recognition_msgs/BoundingBoxArray.msg.

_images/bounding_box_array.png

CameraInfo

Visualize sensor_msgs/CameraInfo.

_images/camera_info.png

_images/camera_info_line.png

Footstep

What is this?

Visualize jsk_footstep_msgs/Footstep.msg.

_images/footstep.png

HumanSkeltonArray

Visualize jsk_recognition_msgs/HumanSkeltonArray

_images/human_skelton_array.png

Normal

This will show the Normal which is subcribed from topic (sensor_msgs::PointCloud2). The normal is assumed to have the features x,y,z,normal_x,normal_y,normal_z.

Normal Plugins in RVizNormal Plugin

Samples

Plug the depth sensor which could be launched by openni.launch and execute below command.

roslaunch jsk_rviz_plugins normal_sample.launch

OverlayText

Draw text of jsk_rviz_plugins/OverlayText on rviz as HUD overlay.

_images/overlay_text.png

Sample

roslaunch jsk_rviz_plugins overlay_sample.launch

PeoplePositionMeasuermentArray

It visualizes people_msgs/PositionMeasuermentArray.

_images/people_position_measurement_array.png

Pictogram

_images/pictogram.pngPictogram

movie

Pictogram is a rviz plugin to visualize icons. Pictogram plugin uses Entypo and FontAwesome.

You need to use jsk_rviz_plugins/Pictogram and jsk_rviz_plugins/PictogramArray message to use it.

You can find mapping with character and icons at here and here.

If you set STRING_MODE, you can show the string popups.

PieChart

Plot a pie chart of std_msgs/Float32 on rviz as HUD overlay.

_images/pie_chart.png

To change caption text, please rename plugin display name on rviz Displays tab

Sample

roslaunch jsk_rviz_plugins overlay_sample.launch

Plotter2D

Plot a line graph of std_msgs/Float32 on rviz as HUD Display.

_images/plotter_2d.png

To change caption text, please rename plugin display name on rviz Displays tab

Sample

roslaunch jsk_rviz_plugins overlay_sample.launch

PolygonArray

_images/polygon_array.pngPolygonArray

Visualize jsk_recognition_msgs/PolygonArray message

Properties

  • Topic

    Name of topic of jsk_recognition_msgs/PolygonArray

  • auto color

    If it’s true, color of polygons are automatically changed

  • Color

    Color of polygons, only enabled if auto color is false

  • Alpha

    Transparency of polygons

  • only border

    Draws only edges of polygons.

  • show normal

    Show normal of polygons.

  • nromal length

    Lenght of normal [m].

RvizScenePublisher

What is this?

RvizScenePublisher plugin can publish sensor_msgs/Image of rviz.

_images/rviz-scene-publisher.gif

Publishing Topic

  • /rviz/image (sensor_msgs/Image)

    Scene of rviz image. You can change the topic name by changing topic_name in Displays.

_images/rviz-scene-publisher.png

SimpleOccupancyGridArray

_images/simple_occupancy_grid_array.png

Visualize jsk_recognition_msgs/SimpleOccupancyGridArray.

String

Draw text of std_msgs/String on rviz as HUD overlay.

_images/string.png

Sample

roslaunch jsk_rviz_plugins overlay_sample.launch

TFTrajectory

_images/tf_trajectory.pnghttps://youtu.be/d9YZWJ5bBZ8

Visualize trajectory of a tf frame.

TorusArray

_images/torus_array.pngTorusArray

Visualize jsk_pcl_ros/TorusArray message

Properties

  • Topic

    Name of topic of jsk_pcl_ros/TorusArray

  • auto color

    If it’s true, color of polygons are automatically changed

  • Color

    Color of polygons, only enabled if auto color is false

  • Alpha

    Transparency of polygons

  • uv-smooth

    Smoothness the surface

  • show normal

    Show normal of toruses.

  • nromal length

    Lenght of normal [m].

TwistStamped

_images/twist_stamped.png

Movie

Visualize geometry_msgs/TwistStamped by arrows. Linear velocity is represented by one arrow and angular velocity is represented by 3 arrows for each axis.

Properties

  • linear scale (default: 1.0)

  • angular scale (default: 1.0)

    Scale factor of size of arrows

  • linear color (default: RGB(0, 255, 0))

  • angular color (default: RGB(255, 0, 0))

    Color of arrows

VideoCapture

VideoCapture plugin can capture video of rviz.

_images/video_capture.png

You need to specify valid filename and fps before capturing video. You can also specify width and height of video manually instead of using 3D viewer size if you want. After that, toggle start capture checkbox and the movie will be recorded until you uncheck the checkbox.

Be careful on creating too large video.

CancelAction

_images/cancel_action.pngCancelAction

This will publish action_msg/GoalID to topic_name/cancel. You can choose multiple cancel goals.

ObjectFitOperatorAction

_images/object_fit_operator_action.pngObjectFitOperatorAction

This will publish jsk_rviz_plugins/ObjectFitCommand to /object_fit_command”. If you check reversed, the reversed version will publish.

PublishTopic

_images/publish_topic.pngPublishTopic

This will publish std_msgs/Empty to the topic you designate.

RecordAction

_images/record_action.pngRecordAction

This will publish jsk_rviz_plugins/RecordCommand to /record_command. Set the target name.

RobotCommandInterfaceAction

_images/robot_command_interface_action.pngRobotCommandInterfaceAction

This will call service to /eus_command with jsk_rviz_plugins/EusCommand srv. All the buttons are configured via ~robot_command_buttons parameters. See robot_command_interface_sample.launch file to know how to use it.

Parameter format is:

robot_command_buttons:
  - name: <name, required>
    icon: <path to icon file, optional>
    type: <"euscommand" or "emptysrv", required>
    command: <S expression to send to eusclient, required if type is euscommand>
    srv: <service name, required if type is "emptysrv">
  - name: ...

SelectPointCloudPublishAction

_images/select_point_cloud_publish_action.pngSelectPointCloudPublishAction

This will publish sensor_msgs/PointCloud2 to /selected_pointcloud.

  1. First, push SelectButton and select the pointcloud region(Note that you need to choose only pointcloud. Don’t include other parts).
  2. Secord, push the SelectPointCloudPublishAction button.
  3. Then the selected pointcloud will be published.

TransformableMarkerOperatorAction

_images/transformable_marker_operator_action_insert.pngTransformableMarkerOperatorAction _images/transformable_marker_operator_action_erase.pngTransformableMarkerOperatorAction

This will call service to /request_marker_operate to insert/erase transformable_object

YesNoButton

Get yes/no user input with rviz button interface.

_images/yes_no_button.gif

Advertising Services

  • /rviz/yes_no_button (jsk_gui_msgs/YesNo)

    Service server to get yes/no user input.

OverlayPickerTool

It is a tool to move overlay plugins interactively.

_images/overlay_picker.gif

If you drag overlay widget with pressing Shift key, the widget is aligned to grid.

ScreenshotListenerTool

It is a tool to take screenshot of rviz via service interface.

Click “add button” of toolbar on rviz and you will see popup to add tools.

_images/screenshot_listener_toolbar.png

_images/screenshot_listener_popup.png

And /rviz/screenshot service will be available.

You can save screenshot via service call:

$ rosservice call /rviz/screenshot foo.png

classification_result_visualizer.py

What is this?

_images/classification_result_visualizer.png

Publish classification results as text markers for each classified object.

The ClassificationResult is synchronized with one topic which represents poses for each classified object / person.

Subscribing Topic

  • ~input/classes (jsk_recognition_msgs/ClassificationResult)

    Classification result

  • ~input/boxes (jsk_recognition_msgs/BoundingBoxArray)

    Bounding boxes of classified objects

  • ~input/poses (geometry_msgs/PoseArray)

    Poses of classified objects

  • ~input/people (jsk_recognition_msgs/PeoplePoseArray)

    Poses of classified people

  • ~input/ObjectDetection (posedetection_msgs/ObjectDetection)

    Poses of classified objects

Publishing Topic

  • ~output (visualization_msgs/MarkerArray)

    Text message markers

Parameters

  • ~appriximate_sync (Bool, Default: false)

    Option to enable approximate synchronization

  • ~queue_size (Int, Default: 100)

    Queue size of subscribers on synchronization

  • ~slop (Double, Default: 0.1)

    Slop duration on approximate synchronization

  • ~text_color_blue (Double, Default: 1.0)

    Blue of text color

  • ~text_color_green (Double, Default: 0.0)

    Green of text color

  • ~text_color_red (Double, Default: 0.0)

    Red of text color

  • ~text_color_alpha (Double, Default: 1.0)

    Alpha of text color

  • ~text_offset_x (Double, Default: 0.0)

    Text offset on x-axis for each object

  • ~text_offset_y (Double, Default: 0.0)

    Text offset on y-axis for each object

  • ~text_offset_z (Double, Default: 0.07)

    Text offset on y-axis for each object

  • ~text_size (Double, Default: 0.05)

    Text size

  • ~marker_lifetime (Double, Default: 5.0)

    Marker lifetime

  • ~show_proba (Bool, Default: true)

    Enable to display probability for each classification

rosconsole_overlay_text.py

What is this?

_images/rosconsole_overlay_text.png

Publish message for overlaying ROS console output on rviz.

Subscribing Topic

  • /rosout (rosgraph_msgs/Log)

    ROS console output.

Publishing Topic

  • ~output (jsk_rviz_plugins/OverlayText)

    Text message displayed on rviz with OverlayText plugin.

Parameters

  • ~nodes (List of String, Default: [])

    Node names whose messages will be published. If an empty list is specified (default), then messages from all nodes will be published.

  • ~nodes_regexp (String, Default: "")

    Regular expression used to filter unmatching nodes. If an empty string is specified (default), then messages from all nodes will be published.

Note that the combination of ~nodes and ~nodes_regexp is AND filter.

  • ~ignore_nodes (List of String, Default: [])

    Node names whose messages won’t be published. This parameter takes priority over ~nodes or nodes_regexp.

  • ~exclude_regexes (List of String, Default: [])

    Regular expressions used to exclude matching messages.

  • ~line_buffer_length (Int, Default: 100)

    Max number of messages stored in buffer.

  • ~reverse_lines (Bool, default: True)

    If True, the order of stored messages in the buffer will be reversed.

Sample

roslaunch jsk_rviz_plugins overlay_sample.launch

jsk_rqt_plugins

rqt_plugins created in JSK Lab.

rqt_2d_plot

_images/rqt_2d_plot.png

Plot data of specified topic as scatter plot.

Topic Type

  • jsk_recognition_msgs/PlotData

Optional Arguments

  • --line: Plot with lines instead of scatter.
  • --fit-line: Plot line with least-square fitting.
  • --fit-line-ransac: Plot line with RANSAC.
  • --fit-line-ransac-outlier: Plot line with RANSAC.

Sample

$ roslaunch jsk_rqt_plugins sample_2dplot.launch

rqt_3d_plot

_images/rqt_3d_plot.png

Plot multiple topics in 3-dimentional layout.

Topic Type

  • numeric data such as std_msgs/Float32

Optional Arguments

  • -P, --pause: Start in paused state.
  • -L, --line: Show lines rather than polygon representation.
  • --no-legend: Do not show legend.
  • -B, --buffer: The length of the buffer. (default = 100)

Sample

$ roslaunch jsk_rqt_plugins sample_3dplot.launch

rqt_drc_mini_maxwell

_images/rqt_drc_mini_maxwell.gif

Subscribe specified topic and show status in facial expression.

Subscribing Topic

  • /drc_2015_environment/is_disabled (std_msgs/Bool)
  • /drc_2015_environment/is_blackout (std_msgs/Bool)
  • /drc_2015_environment/next_whiteout_time (std_msgs/Time)

If is_disabled is True, then it frowns and the background color becomes gray.

If is_disabled is False and is_blackout is True, then it frowns and the background color becomes red. next_whiteout_time is enabled only in this condition.

If is_disabled is False and is_blackout is False, then it smiles and the background color becomes green.

Sample

$ roslaunch jsk_rqt_plugins sample_drc_mini_maxwell.launch

rqt_histogram_plot

_images/rqt_histogram_plot.gif

Plot histogram data. It supported array fields of topics and jsk_recognition_msgs/HistogramWithRange. If you want to specify x-values of figure, use jsk_recognition_msgs/HistogramWithRange.

rqt_image_view2

_images/rqt_image_view2.gif

rqt wrapper of image_view2.

It retrieves image_marked topic from image_view2 and publish event topic to image_view2.

_images/rqt_image_view2_graph.png

Sample

$ roslaunch jsk_rqt_plugins sample_image_view2.launch

rqt_service_buttons

_images/rqt_service_buttons.png

Generate service buttons according to the configuration written in yaml file. (sample yaml file: jsk_rqt_plugins/resource/service_button_layout.yaml)

rqt_status_light

_images/rqt_status_light.png

Subscribe specified topic and show status in a simple color.

Topic Type

  • std_msgs/UInt8

Correspondence between Value and Color

  • 1: green
  • 2: yellow
  • (other): gray

Usage

$ rosrun jsk_rqt_plugins rqt_status_light
$ rostopic pub -r 10 /sample_data std_msgs/UInt8 1  # Select /sample_data in window here

rqt_string_label

_images/rqt_string_label.png

Subscribe string under specified topic and show the string message.

Topic Type

  • Any topic type which has string slot

Usage

$ rosrun jsk_rqt_plugins rqt_string_label
$ rostopic pub -r 10 /sample_string std_msgs/String 'This is a sample string.'  # Select /sample_string/data in window here

rqt_yn_btn

_images/rqt_yn_btn.jpg

Serves yes/no buttons. The buttons are enabled when there is a request.

Advertising Service

Usage

$ rosrun jsk_rqt_plugins rqt_yn_btn rqt_yn_btn:=yes_no
$ rosservice call /yes_no "Select Yes or No"  # push button here
yes: True

jsk_interactive_marker

jsk_interactive_marker is a code using interactive marker.

moveit_msgs/DisplayRobotStateを利用してrviz上にロボットを表示させる

_images/display-robot-state.gif

rviz上に自由にロボットを配置し、可視化するにはmoveit_msgs/DisplayRobotStateが便利です。 これを利用することで、関節角度+ルートリンク位置を指定することでロボットを可視化できます。

サンプルはroslaunch jsk_interactive_marker sample_display_robot_state.launchで確認できます。

moveit_msgs/DisplayRobotStateを利用するためには、moveit_ros_visualizationからRobotStateを選択します. _images/rviz_moveit_robot_state.png

このRobotStateプラグインは2つのパラメータ、1つのトピックに依存します。

  • parameter

    • /robot_description

      ロボットの形状を読むために、robot_descriptionを必要とします。

    • /robot_description_semantic

      moveitで利用される、マニピュレータ情報等を保持するパラメータ。一般にはsrdfというファイルで管理されることが多い。 仮想ジョイントを追加することができるため、これを利用してルートリンクに6自由度の仮想ジョイントを追加してrviz上にロボットを配置させる。

  • topic

    • Robot State Topic (moveit_msgs/DisplayRobotState)

      トピック名はプラグインのフォームで設定可能。

ロボットのルートリンクを指定するため、以下のようなsrdf/robot_description_semanticsに設定する必要があります。

<?xml version="1.0" ?>
<robot name="JAXON_RED">
    <virtual_joint name="world_joint" type="floating" parent_frame="odom" child_link="BODY" />
    <passive_joint name="world_joint" />
</robot>

このsrdfはmoveitでのプランニングを行うためには情報が少なすぎますが、可視化には十分です。 このようなsrdfを自動的に設定するためのスクリプトが package://jsk_interactive_marker/scripts/semantic_robot_state_generator.py として提供されています。

このスクリプトで設定されるsrdfworld_jointという仮想ジョイントがルートリンクとオドメトリ原点との間に設定されます。 これはmoveit標準の命名則と一致しているため、moveit_configで生成したsrdfをsemantic_robot_state_generator.pyの代わりに用いることもできます。

euslispからmoveit_msgs/DisplayRobotStateを生成する関数としてangle-vector-to-display-robot-statepackage://jsk_interactive_marker/euslisp/display-robot-state.lにて提供されています。 これを用いると、以下のようにしてrviz上にロボットを可視化できます。

(load "package://hrpsys_ros_bridge_tutorials/euslisp/jaxon_red-interface.l")
(setq *robot* (instance jaxon_red-robot :init))
(send *robot* :fix-leg-to-coords (make-coords))
(ros::roseus "foo")
(ros::advertise "/robot_state" moveit_msgs::DisplayRobotState)
(ros::publish "/robot_state" (angle-vector-to-display-robot-state *robot* (send (send *robot* :link "BODY") :copy-worldcoords)))

注意点

rvizでRobotStateを追加する前にrobot_description_stateが設定されている必要があります。 そうでないと、ルートリンクの表示がおかしくなります。

marker_6dof

_images/marker_6dof.png

marker_6dof provides interactive marker to control a marker of primitive shape or mesh shape.

Parameters

  • ~object_type (String, default: sphere)

    Type of object shape. cube, sphere, line, and mesh are available.

  • ~frame_id (String, default: /map)

    Frame id of marker.

  • ~publish_tf (Bool, default: False)

    Tf of marker pose is published if true.

  • ~tf_frame (String, default: object)

    frame id of published tf. This value is used only when ~publish_tf is true.

  • ~tf_duration (Double, default: 0.1)

    Time interval of published tf. This value is used only when ~publish_tf is true.

  • ~publish_pose_periodically (Bool, default: False)

    Pose of marker is published periodically if true. Pose topic is published only when marker is moved via Rviz if false.

  • ~object_x (Double, default: 1.0)

  • ~object_y (Double, default: 1.0)

  • ~object_z (Double, default: 1.0)

    X, Y, Z scale of object.

  • ~object_r (Double, default: 1.0)

  • ~object_g (Double, default: 1.0)

  • ~object_b (Double, default: 1.0)

  • ~object_a (Double, default: 1.0)

    Red, Green, Blue and Alpha value of object.

  • ~initial_x (Double, default: 0.0)

  • ~initial_y (Double, default: 0.0)

  • ~initial_z (Double, default: 0.0)

    Initial X, Y, Z position of marker.

  • ~initial_orientation (Vector of Double, default: [0.0, 0.0, 0.0, 1.0])

    Initial orientation of marker described in quaternion.

Subscribing Topics

  • ~feedback (visualization_msgs/InteractiveMarkerFeedback)

  • ~move_marker (geometry_msgs/PoseStamped)

    You can control markers through topics above.

Publishing Topics

  • ~update (visualization_msgs/InteractiveMarkerUpdate)

  • ~update_full (visualization_msgs/InteractiveMarkerInit)

    Current marker state

  • ~pose (geometry_msgs/PoseStamped)

    Pose of marker. You can select publishing policy via ~publish_pose_periodically.

  • /tf (tf2_msgs/TFMessage)

    Tf of marker pose. Available only when ~publish_tf is true.

Sample

roslaunch jsk_interactive_marker marker_6dof_sample.launch

polygon_marker

_images/polygon_marker_anim.gif

polygon_marker is a simple code to provide interactive marker to select one polygon out of multiple polygons represented in jsk_recognition_msgs/PolygonArray.

_images/polygon_marker.png

Subscribing Topics

  • ~polygon_array (jsk_recognition_msgs/PolygonArray)

    Input polygons

Publishing Topics

  • ~selected_index (jsk_recognition_msgs/Int32Stamped)

    Selected index of the polygon.

  • ~selected_polygon (geometry_msgs/PolygonStamped)

    Selected polygon as geometry_msgs/PolygonStamped

  • ~selected_polygon_array (jsk_recognition_msgs/PolygonArray)

    Selected polygon as jsk_recognition_msgs/PolygonArray.

transformable_markers_client.py

_images/transformable_markers_client.gif

transformable_markers_client.py has features below:

  • Insert markers to transformable_server_sample
  • Auto save of user interaction of the markers
  • Publish topics of reusable msgs after conversion from the markers (ex. BOX -> BoundingBox)

Parameters

  • ~config_file (String, requried)

    Config file to insert markers, and auto save the interaction. The format is like below:

boxes:
- name: box_a                        # (requried)
  frame_id: map                      # (optional, default: /map)
  dimensions: [0.09, 0.13, 0.15]     # (optional, default: [1, 1, 1])
  position: [1, 0, 0]                # (optional, default: [0, 0, 0, 1])
  orientation: [0.0, 0.0, 0.0, 1.0]  # (optional, default: [0, 0, 1])
...
  • ~config_auto_save (Bool, default: True)

    Enable the feature to save the config automatically.

Required ROS name

  • ~server

    Node name of transformable_server_sample server.

Publishing Topics

  • ~output/boxes (jsk_recognition_msgs/BoundingBoxArray)

    Converted boxes from marker: BOX -> BoundingBox.

Sample

roslaunch jsk_interactive_marker sample_transformable_markers_client.launch

transformable_server_sample

_images/transformable_marker.png

transformable provides interactive marker to control some object models.

Parameters

  • ~server_name

    Name of interactive server.

  • ~use_parent_and_child (default: false)

    Flag for using ParentAndChildInteractiveServer.

    If true, you can use associate markers like below:

rosservice call /simple_marker/set_parent_marker "parent_topic_name: ''
parent_marker_name: 'drill'
child_marker_name: 'hand'"

If parent_topic_name==empty, it uses self server, and only 1 hierarchy is supported.

  • ~display_interactive_manipulator (Bool, default: true)

    Flat to show the 6dof interactive manipulator for all objects.

  • ~display_interactive_manipulator_only_selected (Bool, default: false)

    Flag to show the 6dof interactive manipulator only for the selected object. This flag does nothing if ~display_interactive_manipulator is false.

  • ~display_description_only_selected (Bool, default: false)

    Flag to show the description only for the selected object.

Usage

roslaunch jsk_interactive_marker urdf_model_marker.launch

then, in different terminal You can insert box marker by this command

rosservice call /simple_marker/request_marker_operate "operate: {type: 0, action: 0, frame_id: '', name: '', description: '', mesh_resource: '',
  mesh_use_embedded_materials: false}"

You can insert model by this command

rosservice call /simple_marker/request_marker_operate "operate: {type: 3, action: 0, frame_id: 'map', name: 'hand', description: '', mesh_resource: 'package://hrpsys_ros_bridge_tutorials/models/HRP3HAND_R_meshes/RARM_LINK6_mesh.dae',
  mesh_use_embedded_materials: true}" 

Topics

You can control markers through topics below (Please Read msg Structure by rosmsg show or some other) (The default topic name is /simple_marker, server name is the same)

  • /simple_marker/set_color
  • /simple_marker/feedback [visualization_msgs/InteractiveMarkerFeedback]
  • /simple_marker/set_radius
  • /simple_marker/set_control_relative_pose
  • /simple_marker/add_pose_relative [geometry_msgs::Pose]
  • /simple_marker/set_z
  • /simple_marker/set_x
  • /simple_marker/set_y
  • /simple_marker/add_pose [geometry_msgs::Pose]
  • /simple_marker/set_control_pose [geometry_msgs::PoseStamped]
  • /simple_marker/set_pose [geometry_msgs::PoseStamped]

You can get marker info by topics below

  • /simple_marker/marker_dimensions [jsk_interactive_marker/MarkerDimensions]
  • /simple_marker/pose [geometry_msgs/PoseStamped]
  • /simple_marker/focus_object_marker_name [std_msgs/String]
  • /simple_marker/pose_with_name [jsk_interactive_marker/PoseStampedWithName]
  • /simple_marker/focus_marker_name_text [jsk_rviz_plugins/OverlayText]
  • /tf [tf2_msgs/TFMessage] (with marker name, tf is published)
  • /simple_marker/focus_marker_pose_text [jsk_rviz_plugins/OverlayText]

Services

You can control markers through topics below

  • /simple_marker/request_marker_operate -> for inserting marker
  • /simple_marker/set_focus
  • /simple_marker/set_color
  • /simple_marker/set_control_pose
  • /simple_marker/set_parameters
  • /simple_marker/set_pose
  • /simple_marker/set_dimensions
  • /simple_marker/set_parent_marker
  • /simple_marker/hide

You can get marker info through topics below

  • /simple_marker/get_control_pose
  • /simple_marker/get_color
  • /simple_marker/get_focus
  • /simple_marker/get_dimensions
  • /simple_marker/get_type
  • /simple_marker/get_pose
  • /simple_marker/get_existence

urdf_model_marker

_images/urdf_model_marker.png

urdf_model_marker provides interactive marker to control robot model.

Parameters

  • ~server_name

    Name of nteractive server.

  • ~use_dynamic_tf (default: true)

    Use dynamic_tf_publisher if it is true.

  • ~model_config

    Collection of parameters.

    • name
    • description
    • scale
    • pose
    • offset
    • use_visible_color
    • frame-id
    • registration
    • fixed_link
    • model
    • use_robot_description
    • model_param
    • robot
    • mode
    • initial_joint_state
      • name
      • position
    • display

Sample

roslaunch jsk_interactive_marker urdf_model_marker.launch

Tips about visualization

Record rviz

kazam

You can use kazam to record desktop movie easily.

sudo apt-get install kazam

glc

You can use glc to record OpenGL rendering. glc is the best way to record OpenGL application because it can record movie efficiently. glc record OpenGL rendering to a special file called .glc and you can convert the .glc into several movie format. It is also good for irtviewer.

Install

You can install glc via ppa package. (see this tutorial)

sudo add-apt-repository ppa:arand/ppa
sudo apt-get update
sudo apt-get install glc
Capture

You can use glc as wrap command like:

glc rviz

If you want to use it in launch file, use launch-prefix attribute:

<node pkg="rviz" type="rviz" name="rviz" launch-prefix="glc" />

You need to type Shift + F8 to start and stop capturing. (see this tutorial for detail)

Convert to movie

You can use glc_encode.sh under jsk_tools.

rosrun jsk_tools glc_encode.sh foo.glc