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

A joint state listener that first reads the robot model from (static) robot_description parameter, and then watches the dynamic model at robot_state_publisher/robot_description. When the dynamic model changes, this listener reloads the 3D representation of the model. More...

#include <joint_state_listener.h>

Inheritance diagram for robot_state_publisher::DynamicJointStateListener:
Inheritance graph
[legend]

Public Member Functions

 DynamicJointStateListener (const Tree &tree, const MimicMap &m, const urdf::Model &model)
 Construct the listener using the given KDL tree, URDF model and mimic map. More...
 
bool reloadRobotModel (const std::string &urdf="")
 Reload the robot model. More...
 
- Public Member Functions inherited from robot_state_publisher::JointStateListener
 JointStateListener (const KDL::Tree &tree, const MimicMap &m, const urdf::Model &model=urdf::Model())
 
 ~JointStateListener ()
 

Static Public Member Functions

static bool loadModel (KDL::Tree &tree, MimicMap &mimic_map, urdf::Model &model, const std::string &urdf="")
 Parses the given URDF string (or robot_description param if the string is empty) to a KDL tree, URDF model and a mimic map. More...
 

Protected Member Functions

void callbackJointState (const JointStateConstPtr &state) override
 Called when new joint state arrives. More...
 
void configChangedCb (DynamicRobotStateConfig &config, uint32_t level)
 The callback that is called whenever the dynamic robot model changes. More...
 
- Protected Member Functions inherited from robot_state_publisher::JointStateListener
virtual void callbackFixedJoint (const ros::TimerEvent &e)
 

Protected Attributes

DynamicRobotStatePublisher dynamicPublisher
 The RobotStatePublisher with update functionality. More...
 
dynamic_reconfigure::Server< DynamicRobotStateConfig > dynparamServer
 The dynamic parameter server. More...
 
std::mutex updateOngoing
 Mutex for updates. More...
 
- Protected Attributes inherited from robot_state_publisher::JointStateListener
bool ignore_timestamp_
 
Subscriber joint_state_sub_
 
ros::Time last_callback_time_
 
std::map< std::string, ros::Timelast_publish_time_
 
MimicMap mimic_
 
Duration publish_interval_
 
robot_state_publisher::RobotStatePublisher state_publisher_
 
std::string tf_prefix_
 
ros::Timer timer_
 
bool use_tf_static_
 

Detailed Description

A joint state listener that first reads the robot model from (static) robot_description parameter, and then watches the dynamic model at robot_state_publisher/robot_description. When the dynamic model changes, this listener reloads the 3D representation of the model.

Definition at line 20 of file joint_state_listener.h.

Constructor & Destructor Documentation

robot_state_publisher::DynamicJointStateListener::DynamicJointStateListener ( const Tree &  tree,
const MimicMap m,
const urdf::Model model 
)

Construct the listener using the given KDL tree, URDF model and mimic map.

Parameters
[in]treeParsed KDL tree.
[in]mMimic map.
[in]modelURDF model.

Definition at line 47 of file joint_state_listener.cpp.

Member Function Documentation

void robot_state_publisher::DynamicJointStateListener::callbackJointState ( const JointStateConstPtr state)
overrideprotectedvirtual

Called when new joint state arrives.

Parameters
[in]stateThe joint state to process.

Reimplemented from robot_state_publisher::JointStateListener.

Definition at line 88 of file joint_state_listener.cpp.

void robot_state_publisher::DynamicJointStateListener::configChangedCb ( DynamicRobotStateConfig &  config,
uint32_t  level 
)
protected

The callback that is called whenever the dynamic robot model changes.

Parameters
configThe updated config.
levelNonzero on startup, zero otherwise.

Definition at line 104 of file joint_state_listener.cpp.

bool robot_state_publisher::DynamicJointStateListener::loadModel ( KDL::Tree tree,
MimicMap mimic_map,
urdf::Model model,
const std::string &  urdf = "" 
)
static

Parses the given URDF string (or robot_description param if the string is empty) to a KDL tree, URDF model and a mimic map.

Parameters
[out]treeThe parsed KDL tree.
[out]mimic_mapThe parsed mimic map.
[out]Theparsed URDF model.
[in]urdfIf empty, parse the model from (static) param robot_description, otherwise parse it from the given string.
Returns
True if the model was correctly read and parsed.

Definition at line 5 of file joint_state_listener.cpp.

bool robot_state_publisher::DynamicJointStateListener::reloadRobotModel ( const std::string &  urdf = "")

Reload the robot model.

Parameters
[in]urdfIf empty, load it from (static) param robot_description, otherwise load it from the given string.
Returns
True if the model was correctly read and parsed.

make sure that state_publisher is not currently publishing

allow publishFixedTransforms to end

fixed transforms are published again

Definition at line 61 of file joint_state_listener.cpp.

Member Data Documentation

DynamicRobotStatePublisher robot_state_publisher::DynamicJointStateListener::dynamicPublisher
protected

The RobotStatePublisher with update functionality.

Definition at line 66 of file joint_state_listener.h.

dynamic_reconfigure::Server<DynamicRobotStateConfig> robot_state_publisher::DynamicJointStateListener::dynparamServer
protected

The dynamic parameter server.

Definition at line 69 of file joint_state_listener.h.

std::mutex robot_state_publisher::DynamicJointStateListener::updateOngoing
protected

Mutex for updates.

Definition at line 63 of file joint_state_listener.h.


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


dynamic_robot_state_publisher
Author(s): Martin Pecka
autogenerated on Mon Jun 10 2019 13:05:57