45 int main(
int argc,
char** argv)
48 ros::init(argc, argv,
"robot_state_publisher");
52 std::string exe_name = argv[0];
53 std::size_t slash = exe_name.find_last_of(
"/");
54 if (slash != std::string::npos) {
55 exe_name = exe_name.substr(slash + 1);
57 if (exe_name ==
"state_publisher") {
58 ROS_WARN(
"The 'state_publisher' executable is deprecated. Please use 'robot_state_publisher' instead");
64 if (!model.
initParam(
"robot_description"))
69 ROS_ERROR(
"Failed to extract kdl tree from xml robot description");
75 for(std::map< std::string, urdf::JointSharedPtr >::iterator i = model.joints_.begin(); i != model.joints_.end(); i++) {
76 if(i->second->mimic) {
77 mimic.insert(make_pair(i->first, i->second->mimic));
KDL_PARSER_PUBLIC bool treeFromUrdfModel(const urdf::ModelInterface &robot_model, KDL::Tree &tree)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
URDF_EXPORT bool initParam(const std::string ¶m)
std::map< std::string, urdf::JointMimicSharedPtr > MimicMap