An alternative RobotStatePublisher with update option.
More...
#include <robot_state_publisher.h>
|
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...
|
|
An alternative RobotStatePublisher with update option.
Definition at line 11 of file robot_state_publisher.h.
◆ DynamicRobotStatePublisher()
◆ addChildren()
void robot_state_publisher::DynamicRobotStatePublisher::addChildren |
( |
const KDL::SegmentMap::const_iterator |
segment | ) |
|
|
protectedvirtual |
◆ getFixedSegments() [1/2]
const std::map< std::string, SegmentPair > & robot_state_publisher::DynamicRobotStatePublisher::getFixedSegments |
( |
| ) |
|
|
protected |
◆ 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 |
◆ getSegments() [2/2]
const std::map<std::string, SegmentPair>& robot_state_publisher::DynamicRobotStatePublisher::getSegments |
( |
| ) |
const |
|
protected |
◆ getStaticTfBroadcaster()
◆ updateTree()
void robot_state_publisher::DynamicRobotStatePublisher::updateTree |
( |
const KDL::Tree & |
tree | ) |
|
|
virtual |
Sets the robot model.
- Parameters
-
tree | The 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.
◆ 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
The documentation for this class was generated from the following files: