2 #include <kdl/tree.hpp> 7 int main(
int argc,
char** argv)
10 ros::init(argc, argv,
"robot_state_publisher");
17 tree, mimic, model,
"");
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