Class RobotStatePublisher

Inheritance Relationships

Base Type

  • public rclcpp::Node

Class Documentation

class RobotStatePublisher : public rclcpp::Node

The class that contains all of the functionality of the RobotStatePublisher ROS 2 node.

Public Functions

explicit RobotStatePublisher(const rclcpp::NodeOptions &options)

Constructor.

Protected Functions

KDL::Tree parseURDF(const std::string &urdf_xml, urdf::Model &model)
void setupURDF(const std::string &urdf_xml)

Setup the URDF for use.

This method first parses the URDF into an internal representation. Based on that representation, it then generates the list of joint segments and mimic pairs that it needs during runtime. Finally, it publishes the text of the URDF to the network on the /robot_description topic.

Parameters:

urdf_xml[in] The string representing the URDF XML.

void addChildren(const urdf::Model &model, const KDL::SegmentMap::const_iterator segment)

Recursive method to add all children to the internal segment list.

Parameters:

segment[in] An iterator to the SegmentMap to add to the internal segment list.

void publishTransforms(const std::map<std::string, double> &joint_positions, const builtin_interfaces::msg::Time &time)

Publish transforms to /tf2.

This method is called by callbackJointState() when new transforms are available and need to be published.

Parameters:
  • joint_positions[in] A map of joint names to joint positions.

  • time[in] The time at which the joint positions were recorded.

void publishFixedTransforms()

Publish fixed transforms at startup time to /tf2_static.

void callbackJointState(const sensor_msgs::msg::JointState::ConstSharedPtr state)

The callback that is called when a new JointState message is received.

This method examines the incoming JointStates and applies a series of checks to see if new transforms should be published. If so, it calls publishTransforms() to do so.

Parameters:

state[in] The JointState message that was delivered.

rcl_interfaces::msg::SetParametersResult parameterUpdate(const std::vector<rclcpp::Parameter> &parameters)

The callback that is called to check that new parameters are valid.

This allows the class to reject parameter updates that are invalid.

Parameters:

parameters[in] The vector of parameters that are going to change.

Returns:

SetParametersResult with successful set to true on success, false otherwise.

void onParameterEvent(std::shared_ptr<const rcl_interfaces::msg::ParameterEvent> event)

The callback that is called when parameters on the node are changed.

This allows the class to dynamically react to changes in parameters.

Parameters:

event[in] The parameter change event that occurred.

Protected Attributes

std::map<std::string, SegmentPair> segments_

A map of dynamic segment names to SegmentPair structures.

std::map<std::string, SegmentPair> segments_fixed_

A map of fixed segment names to SegmentPair structures.

std::unique_ptr<tf2_ros::TransformBroadcaster> tf_broadcaster_

A pointer to the tf2 TransformBroadcaster.

std::unique_ptr<tf2_ros::StaticTransformBroadcaster> static_tf_broadcaster_

A pointer to the tf2 StaticTransformBroadcaster.

rclcpp::Publisher<std_msgs::msg::String>::SharedPtr description_pub_

A pointer to the ROS 2 publisher for the robot_description.

rclcpp::Subscription<sensor_msgs::msg::JointState>::SharedPtr joint_state_sub_

A pointer to the ROS 2 subscription for the joint states.

rclcpp::Time last_callback_time_

The last time a joint state message was received.

std::map<std::string, builtin_interfaces::msg::Time> last_publish_time_

A map between a joint name and the last time its state was published.

MimicMap mimic_

A map of the mimic joints that should be published.

rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr param_cb_

The parameter event callback that will be called when a parameter is changed.

std::shared_ptr<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent, std::allocator<void>>> parameter_subscription_

The parameter event callback that will be called when a parameter is changed.