Builder creates a visualization of a robot, given its URDF model. More...
#include <builder.h>
Public Member Functions | |
void | Build (visualization_msgs::MarkerArray *marker_array) |
Builds a visualization of the robot model as a marker array. | |
void | Build (const std::set< std::string > &link_names, visualization_msgs::MarkerArray *marker_array) |
Builds a subset of the robot model visualization as a marker array. | |
Builder (const urdf::Model &model) | |
Construct a Builder with the given URDF model. | |
void | Init () |
Initializes the Builder. | |
void | SetColor (float r, float g, float b, float a) |
Sets the color of the robot. | |
void | SetFrameId (const std::string &frame_id) |
Set the output frame ID. | |
void | SetFrameLocked (bool frame_locked) |
Sets whether the marker should be locked to its frame ID. | |
void | SetJointPositions (const std::map< std::string, double > joint_positions) |
Set the joint angles on the robot. | |
void | SetLifetime (const ros::Duration &lifetime) |
Sets the lifetime of the robot markers. | |
void | SetNamespace (const std::string &ns) |
Set the marker namespace. | |
void | SetPose (const geometry_msgs::Pose &pose) |
Set the pose of the robot, in the frame ID given by SetFrameId. | |
void | SetTime (const ros::Time &stamp) |
Set the time stamp. | |
Private Member Functions | |
void | BuildMarker (const urdf::Link &link, int id, visualization_msgs::Marker *output) |
std::string | NodeName (const std::string &name) |
Private Attributes | |
std_msgs::ColorRGBA | color_ |
ForwardKinematics | fk_ |
std::string | frame_id_ |
bool | frame_locked_ |
bool | has_initialized_ |
ros::Duration | lifetime_ |
urdf::Model | model_ |
std::string | ns_ |
geometry_msgs::Pose | pose_ |
ros::Time | stamp_ |
transform_graph::Graph | tf_graph_ |
Builder creates a visualization of a robot, given its URDF model.
You can either get the visualization as a visualization_msgs::MarkerArray or as a visualization_msgs::InteractiveMarker. The visualization is based on the URDF and should represent the robot with all joint positions set to 0. However, you can set the joint positions before building the marker.
The API uses a builder pattern. You first create a builder with the URDF and initialize it (Init). Then, you set the namespace (the marker IDs start at 0 and count up), time stamp, frame ID, pose, color, etc. If no color is provided or the color values are all 0, the mesh color will be used.
Once you have set all the marker fields, you then call Build to get the marker or markers representing the robot.
Example:
// Robot 1: Default configuration. visualization_msgs::MarkerArray robot1; builder.SetNamespace("robot"); builder.SetFrameId("base_link"); builder.SetTime(ros::Time::now()); builder.Build(&robot1); marker_arr_pub.publish(robot1); // Robot 2: Different pose and joints changed. visualization_msgs::MarkerArray robot2; builder.SetNamespace("robot2"); std::map<std::string, double> joint_positions; joint_positions["torso_lift_joint"] = 0.1; joint_positions["head_tilt_joint"] = 0.5; builder.SetJointPositions(joint_positions); geometry_msgs::Pose pose; pose.position.y = 1; pose.orientation.w = 0.92387953; pose.orientation.z = -0.38268343; builder.SetPose(pose); builder.Build(&robot2); marker_arr_pub.publish(robot2);
It is also possible to filter the markers to a subset of the links. For example, to just get the markers for the left gripper of a PR2:
std::set<std::string> gripper_links; gripper_links.insert("l_gripper_palm_link"); gripper_links.insert("l_gripper_l_finger_link"); gripper_links.insert("l_gripper_l_finger_tip_link"); gripper_links.insert("l_gripper_r_finger_link"); gripper_links.insert("l_gripper_r_finger_tip_link"); builder.Build(gripper_links, &marker_array);
Note that the pose of the gripper will still be where it would have been if you had rendered the whole robot. If you want to move the gripper to an arbitrary pose, you will need to transform all the gripper markers yourself.
robot_markers::Builder::Builder | ( | const urdf::Model & | model | ) | [explicit] |
Construct a Builder with the given URDF model.
Definition at line 58 of file builder.cpp.
void robot_markers::Builder::Build | ( | visualization_msgs::MarkerArray * | marker_array | ) |
Builds a visualization of the robot model as a marker array.
It sets marker properties according to the Set* methods in the class. You can build multiple sets of markers with the same builder, but you should be mindful of the history of property settings made beforehand.
[out] | marker_array | The marker array message to append to. |
void robot_markers::Builder::Build | ( | const std::set< std::string > & | link_names, |
visualization_msgs::MarkerArray * | marker_array | ||
) |
Builds a subset of the robot model visualization as a marker array.
It sets marker properties according to the Set* methods in the class. You can build multiple sets of markers with the same builder, but you should be mindful of the history of property settings made beforehand.
[in] | link_names | The names of the links to visualize. |
[out] | marker_array | The marker array message to append to. |
void robot_markers::Builder::BuildMarker | ( | const urdf::Link & | link, |
int | id, | ||
visualization_msgs::Marker * | output | ||
) | [private] |
Definition at line 215 of file builder.cpp.
void robot_markers::Builder::Init | ( | ) |
Initializes the Builder.
Call Init() once before calling any other methods. This does NOT set any marker parameters (color, pose, etc.).
Definition at line 73 of file builder.cpp.
std::string robot_markers::Builder::NodeName | ( | const std::string & | name | ) | [private] |
Definition at line 261 of file builder.cpp.
void robot_markers::Builder::SetColor | ( | float | r, |
float | g, | ||
float | b, | ||
float | a | ||
) |
Sets the color of the robot.
Set to 0, 0, 0, 0 to use the mesh colors if available. If the mesh contains color information, then setting a non-zero color will tint the robot in that color.
[in] | r | The red value, between 0 and 1. |
[in] | g | The green value, between 0 and 1. |
[in] | b | The blue value, between 0 and 1. |
[in] | a | The alpha value, between 0 and 1. |
Definition at line 153 of file builder.cpp.
void robot_markers::Builder::SetFrameId | ( | const std::string & | frame_id | ) |
Set the output frame ID.
All the markers will be given in this frame.
[in] | frame_id | The frame ID for all the markers. |
Definition at line 115 of file builder.cpp.
void robot_markers::Builder::SetFrameLocked | ( | bool | frame_locked | ) |
Sets whether the marker should be locked to its frame ID.
The frame ID is supplied via SetFrameId.
[in] | frame_locked | True to lock the markers to the robot's frame ID, false otherwise. |
void robot_markers::Builder::SetJointPositions | ( | const std::map< std::string, double > | joint_positions | ) |
Set the joint angles on the robot.
If the robot does not have a joint, an error will be logged and the visualization will be unchanged.
[in] | joint_positions | The joint angles/positions to set. This method does not check joint limits, so you must supply valid values. |
Definition at line 95 of file builder.cpp.
void robot_markers::Builder::SetLifetime | ( | const ros::Duration & | lifetime | ) |
Sets the lifetime of the robot markers.
[in] | lifetime | The lifetime for the robot markers. |
void robot_markers::Builder::SetNamespace | ( | const std::string & | ns | ) |
Set the marker namespace.
Note that you cannot set the IDs of the markers. To visualize multiple robots, give each their own namespace.
[in] | ns | The namespace for all the markers. |
Definition at line 135 of file builder.cpp.
void robot_markers::Builder::SetPose | ( | const geometry_msgs::Pose & | pose | ) |
Set the pose of the robot, in the frame ID given by SetFrameId.
[in] | pose | The pose of the robot. |
Definition at line 144 of file builder.cpp.
void robot_markers::Builder::SetTime | ( | const ros::Time & | stamp | ) |
Set the time stamp.
All the markers will be given this time stamp.
[in] | stamp | The time stamp for all the markers. |
Definition at line 125 of file builder.cpp.
std_msgs::ColorRGBA robot_markers::Builder::color_ [private] |
ForwardKinematics robot_markers::Builder::fk_ [private] |
std::string robot_markers::Builder::frame_id_ [private] |
bool robot_markers::Builder::frame_locked_ [private] |
bool robot_markers::Builder::has_initialized_ [private] |
urdf::Model robot_markers::Builder::model_ [private] |
std::string robot_markers::Builder::ns_ [private] |
ros::Time robot_markers::Builder::stamp_ [private] |