35 const std::vector<URDFName>& joint_names_in_urdf,
36 const URDFName& base_joint_in_urdf,
37 const std::string& fixed_frame,
38 const std::string& state_topic,
39 const std::string& tf_prefix)
51 KDL::Tree my_kdl_tree;
53 bool model_ok = my_urdf_model.
initParam(urdf_name);
63 robot_publisher = std::make_shared<robot_state_publisher::RobotStatePublisher>(my_kdl_tree);
82 for (
int i=0; i<msg.position.size(); ++i)
88 geometry_msgs::TransformStamped
90 const geometry_msgs::Pose &msg)
const
93 geometry_msgs::TransformStamped W_X_B_message;
94 W_X_B_message.header.stamp = stamp;
98 W_X_B_message.transform.translation.x = msg.position.x;
99 W_X_B_message.transform.translation.y = msg.position.y;
100 W_X_B_message.transform.translation.z = msg.position.z;
102 W_X_B_message.transform.rotation.w = msg.orientation.w;
103 W_X_B_message.transform.rotation.x = msg.orientation.x;
104 W_X_B_message.transform.rotation.y = msg.orientation.y;
105 W_X_B_message.transform.rotation.z = msg.orientation.z;
107 return W_X_B_message;