joint_state_listener.h
Go to the documentation of this file.
1 #ifndef DYNAMIC_ROBOT_STATE_PUBLISHER_JOINT_STATE_LISTENER_H
2 #define DYNAMIC_ROBOT_STATE_PUBLISHER_JOINT_STATE_LISTENER_H
3 
4 #include <mutex>
5 
6 #include <dynamic_reconfigure/server.h>
7 
8 #include <robot_state_publisher/joint_state_listener.h>
10 #include <dynamic_robot_state_publisher/DynamicRobotStateConfig.h>
11 
12 namespace robot_state_publisher
13 {
21 {
22 public:
31  const Tree &tree, const MimicMap &m, const urdf::Model &model);
32 
39  bool reloadRobotModel(const std::string &urdf = "");
40 
52  static bool loadModel(KDL::Tree &tree, MimicMap &mimic_map,
53  urdf::Model &model, const std::string &urdf = "");
54 
55 protected:
60  void callbackJointState(const JointStateConstPtr &state) override;
61 
63  std::mutex updateOngoing;
64 
67 
69  dynamic_reconfigure::Server<DynamicRobotStateConfig> dynparamServer;
70 
76  void configChangedCb(DynamicRobotStateConfig &config, uint32_t level);
77 
78 };
79 }
80 
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.
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


dynamic_robot_state_publisher
Author(s): Martin Pecka
autogenerated on Mon Mar 18 2019 02:25:19