dynamic_robot_state_publisher_node.cpp
Go to the documentation of this file.
1 #include <urdf/model.h>
2 #include <kdl/tree.hpp>
4 
6 
7 int main(int argc, char** argv)
8 {
9  // Initialize ros
10  ros::init(argc, argv, "robot_state_publisher");
11  NodeHandle node;
12 
13  urdf::Model model;
14  KDL::Tree tree;
15  MimicMap mimic;
17  tree, mimic, model, "");
18 
20  tree, mimic, model);
21 
22  ros::spin();
23 
24  return 0;
25 }
A joint state listener that first reads the robot model from (static) robot_description parameter...
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL void spin(Spinner &spinner)
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...
int main(int argc, char **argv)
std::map< std::string, urdf::JointMimicSharedPtr > MimicMap


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