1 #ifndef DYNAMIC_ROBOT_STATE_PUBLISHER_JOINT_STATE_LISTENER_H 2 #define DYNAMIC_ROBOT_STATE_PUBLISHER_JOINT_STATE_LISTENER_H 6 #include <dynamic_reconfigure/server.h> 8 #include <robot_state_publisher/joint_state_listener.h> 10 #include <dynamic_robot_state_publisher/DynamicRobotStateConfig.h> 81 #endif //DYNAMIC_ROBOT_STATE_PUBLISHER_JOINT_STATE_LISTENER_H void configChangedCb(DynamicRobotStateConfig &config, uint32_t level)
The callback that is called whenever the dynamic robot model changes.
std::mutex updateOngoing
Mutex for updates.
void callbackJointState(const JointStateConstPtr &state) override
Called when new joint state arrives.
A joint state listener that first reads the robot model from (static) robot_description parameter...
bool reloadRobotModel(const std::string &urdf="")
Reload the robot model.
An alternative RobotStatePublisher with update option.
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...
DynamicRobotStatePublisher dynamicPublisher
The RobotStatePublisher with update functionality.
DynamicJointStateListener(const Tree &tree, const MimicMap &m, const urdf::Model &model)
Construct the listener using the given KDL tree, URDF model and mimic map.
dynamic_reconfigure::Server< DynamicRobotStateConfig > dynparamServer
The dynamic parameter server.
std::map< std::string, urdf::JointMimicSharedPtr > MimicMap