35 const std::vector<URDFName>& joint_names_in_urdf,
37 const std::string& fixed_frame,
38 const std::string& state_topic,
39 const std::string& tf_prefix)
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;
std::string getTopic() const
void StateCallback(const xpp_msgs::RobotStateJoint &msg)
KDL_PARSER_PUBLIC bool treeFromUrdfModel(const urdf::ModelInterface &robot_model, KDL::Tree &tree)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
tf::TransformBroadcaster tf_broadcaster_
UrdfnameToJointAngle AssignAngleToURDFJointName(const sensor_msgs::JointState &msg) const
std::map< URDFName, double > UrdfnameToJointAngle
std::shared_ptr< robot_state_publisher::RobotStatePublisher > robot_publisher
std::vector< URDFName > joint_names_in_urdf_
std::string rviz_fixed_frame_
URDF_EXPORT bool initParam(const std::string ¶m)
UrdfVisualizer(const std::string &urdf_name, const std::vector< URDFName > &joint_names_in_urdf, const URDFName &base_link_in_urdf, const std::string &rviz_fixed_frame, const std::string &state_topic, const std::string &tf_prefix="")
Constructs the visualizer for a specific URDF urdf_name.
URDFName base_joint_in_urdf_
geometry_msgs::TransformStamped GetBaseFromRos(const ::ros::Time &stamp, const geometry_msgs::Pose &msg) const
ros::Subscriber state_sub_des_