30 #ifndef XPP_VIS_URDF_VISUALIZER_H_ 31 #define XPP_VIS_URDF_VISUALIZER_H_ 44 #include <sensor_msgs/JointState.h> 48 #include <xpp_msgs/RobotStateJoint.h> 79 const std::vector<URDFName>& joint_names_in_urdf,
81 const std::string& rviz_fixed_frame,
82 const std::string& state_topic,
83 const std::string& tf_prefix =
"");
94 geometry_msgs::TransformStamped
GetBaseFromRos(const ::ros::Time& stamp,
95 const geometry_msgs::Pose &msg)
const;
void StateCallback(const xpp_msgs::RobotStateJoint &msg)
tf::TransformBroadcaster tf_broadcaster_
UrdfnameToJointAngle AssignAngleToURDFJointName(const sensor_msgs::JointState &msg) const
virtual ~UrdfVisualizer()=default
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_
std::string state_msg_name_
Publishes RVIZ transforms used to visualize a robot's URDF.
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_