[Documentation] [TitleIndex] [WordIndex

Only released in EOL distros:  

Package Summary

Generates markers for a robot

Use GitHub to report bugs or submit feature requests. [View active issues]

Overview

robot_markers is a library for creating RViz markers for a robot, given a URDF.

demo.png

Quick start

The library's generated documentation explains how to use robot_markers.

robot_markers::Builder is the main interface for building a MarkerArray from a URDF.

First, create a Builder for a given URDF:

   1 #include "robot_markers/builder.h"
   2 #include "ros/ros.h"
   3 #include "urdf/model.h"
   4 
   5 urdf::Model model;
   6 model.initParam("robot_description");
   7 
   8 robot_markers::Builder builder(model);
   9 builder.Init();

There are a variety of configuration options you can set before generating the markers (pose, color, etc.). You should always specify a namespace and a frame ID.

   1 builder.SetNamespace("robot");
   2 builder.SetFrameId("base_link");
   3 builder.SetColor(0.33, 0.17, 0.45, 1); // A color of 0, 0, 0, 0 means to use the mesh colors.
   4 geometry_msgs::Pose pose;
   5 pose.position.y = 1;
   6 pose.orientation.w = 0.92387953;
   7 pose.orientation.z = -0.38268343;
   8 builder.SetPose(pose);

A notable feature of Builder is the ability to set the joint angles of the robot. To do so, pass in a map that gives the joint angles for a set of joint names. Builder does not check joint angle limits.

   1 #include <map>
   2 #include <string>
   3 
   4 std::map<std::string, double> joint_positions;
   5 joint_positions["torso_lift_joint"] = 0.1;
   6 joint_positions["head_tilt_joint"] = 0.5;
   7 builder.SetJointPositions(joint_positions);

Once you have configured the visualization, call Builder::Build, passing in a marker array to append the robot markers to.

   1 ros::Publisher marker_arr_pub =
   2   nh.advertise<visualization_msgs::MarkerArray>("robot", 10);
   3 visualization_msgs::MarkerArray robot1;
   4 builder.Build(&robot1);
   5 marker_arr_pub.publish(robot1);

Here is a full example, available as a demo file.

   1 #include <map>
   2 #include <string>
   3 
   4 #include "geometry_msgs/Pose.h"
   5 #include "robot_markers/builder.h"
   6 #include "ros/ros.h"
   7 #include "urdf/model.h"
   8 #include "visualization_msgs/MarkerArray.h"
   9 
  10 int main(int argc, char** argv) {
  11   ros::init(argc, argv, "robot_markers_demo");
  12   ros::NodeHandle nh;
  13   ros::Publisher marker_arr_pub =
  14       nh.advertise<visualization_msgs::MarkerArray>("robot", 10);
  15   ros::Duration(0.5).sleep();
  16 
  17   urdf::Model model;
  18   model.initParam("robot_description");
  19 
  20   robot_markers::Builder builder(model);
  21   builder.Init();
  22 
  23   // Robot 1: Default configuration, purple.
  24   visualization_msgs::MarkerArray robot1;
  25   builder.SetNamespace("robot");
  26   builder.SetFrameId("base_link");
  27   builder.SetColor(0.33, 0.17, 0.45, 1);
  28   builder.Build(&robot1);
  29   marker_arr_pub.publish(robot1);
  30 
  31   // Robot 2: Different pose, joints changed.
  32   visualization_msgs::MarkerArray robot2;
  33   builder.SetNamespace("robot2");
  34   builder.SetColor(0, 0, 0, 0);
  35 
  36   std::map<std::string, double> joint_positions;
  37   joint_positions["torso_lift_joint"] = 0.1;
  38   joint_positions["head_tilt_joint"] = 0.5;
  39   builder.SetJointPositions(joint_positions);
  40 
  41   geometry_msgs::Pose pose;
  42   pose.position.y = 1;
  43   pose.orientation.w = 0.92387953;
  44   pose.orientation.z = -0.38268343;
  45   builder.SetPose(pose);
  46   builder.Build(&robot2);
  47   marker_arr_pub.publish(robot2);
  48 
  49   ros::Duration(0.5).sleep();
  50 
  51   return 0;
  52 }


2023-10-28 12:57