Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | List of all members
robot_state_publisher::DynamicRobotStatePublisher Class Reference

An alternative RobotStatePublisher with update option. More...

#include <robot_state_publisher.h>

Public Member Functions

 DynamicRobotStatePublisher (RobotStatePublisher *publisher)
 Create the publisher. More...
 
virtual size_t getNumFixedJoints () const
 Return the number of fixed joints in the currently represented model. More...
 
virtual size_t getNumMovingJoints () const
 Return the number of moving joints in the currently represented model. More...
 
virtual void updateTree (const KDL::Tree &tree)
 Sets the robot model. More...
 

Public Attributes

const std::string DELETED_STATIC_TFS_FRAME = "__deleted_static_tfs__"
 The TF frame name of the virtual frame that's parent of all deleted static TF frames. More...
 

Protected Member Functions

virtual void addChildren (const KDL::SegmentMap::const_iterator segment)
 
std::map< std::string, SegmentPair > & getFixedSegments ()
 
const std::map< std::string, SegmentPair > & getFixedSegments () const
 
std::map< std::string, SegmentPair > & getSegments ()
 
const std::map< std::string, SegmentPair > & getSegments () const
 
tf2_ros::StaticTransformBroadcastergetStaticTfBroadcaster ()
 

Protected Attributes

RobotStatePublisherpublisher
 The underlying (hacked) publisher. More...
 

Detailed Description

An alternative RobotStatePublisher with update option.

Definition at line 11 of file robot_state_publisher.h.

Constructor & Destructor Documentation

◆ DynamicRobotStatePublisher()

robot_state_publisher::DynamicRobotStatePublisher::DynamicRobotStatePublisher ( robot_state_publisher::RobotStatePublisher publisher)
explicit

Create the publisher.

Parameters
[in]publisherThe underlying RobotStatePublisher that is hijacked.

Definition at line 65 of file robot_state_publisher.cpp.

Member Function Documentation

◆ addChildren()

void robot_state_publisher::DynamicRobotStatePublisher::addChildren ( const KDL::SegmentMap::const_iterator  segment)
protectedvirtual

Definition at line 127 of file robot_state_publisher.cpp.

◆ getFixedSegments() [1/2]

const std::map< std::string, SegmentPair > & robot_state_publisher::DynamicRobotStatePublisher::getFixedSegments ( )
protected

Definition at line 90 of file robot_state_publisher.cpp.

◆ getFixedSegments() [2/2]

const std::map<std::string, SegmentPair>& robot_state_publisher::DynamicRobotStatePublisher::getFixedSegments ( ) const
protected

◆ getNumFixedJoints()

size_t robot_state_publisher::DynamicRobotStatePublisher::getNumFixedJoints ( ) const
virtual

Return the number of fixed joints in the currently represented model.

Returns
The number of fixed joints in the currently represented model.

Definition at line 76 of file robot_state_publisher.cpp.

◆ getNumMovingJoints()

size_t robot_state_publisher::DynamicRobotStatePublisher::getNumMovingJoints ( ) const
virtual

Return the number of moving joints in the currently represented model.

Returns
The number of moving joints in the currently represented model.

Definition at line 71 of file robot_state_publisher.cpp.

◆ getSegments() [1/2]

const std::map< std::string, SegmentPair > & robot_state_publisher::DynamicRobotStatePublisher::getSegments ( )
protected

Definition at line 81 of file robot_state_publisher.cpp.

◆ getSegments() [2/2]

const std::map<std::string, SegmentPair>& robot_state_publisher::DynamicRobotStatePublisher::getSegments ( ) const
protected

◆ getStaticTfBroadcaster()

tf2_ros::StaticTransformBroadcaster & robot_state_publisher::DynamicRobotStatePublisher::getStaticTfBroadcaster ( )
protected

Definition at line 117 of file robot_state_publisher.cpp.

◆ updateTree()

void robot_state_publisher::DynamicRobotStatePublisher::updateTree ( const KDL::Tree &  tree)
virtual

Sets the robot model.

Parameters
treeThe kinematic model of a robot, represented by a KDL Tree.

function is only called from JointStateListener::reload_robot_model where the update mutex is acquired

Definition at line 25 of file robot_state_publisher.cpp.

Member Data Documentation

◆ DELETED_STATIC_TFS_FRAME

const std::string robot_state_publisher::DynamicRobotStatePublisher::DELETED_STATIC_TFS_FRAME = "__deleted_static_tfs__"

The TF frame name of the virtual frame that's parent of all deleted static TF frames.

Definition at line 21 of file robot_state_publisher.h.

◆ publisher

RobotStatePublisher* robot_state_publisher::DynamicRobotStatePublisher::publisher
protected

The underlying (hacked) publisher.

Definition at line 68 of file robot_state_publisher.h.


The documentation for this class was generated from the following files:


dynamic_robot_state_publisher
Author(s): Martin Pecka
autogenerated on Fri May 6 2022 02:34:15