Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 #include <xpp_vis/urdf_visualizer.h>
00031 
00032 namespace xpp {
00033 
00034 UrdfVisualizer::UrdfVisualizer(const std::string& urdf_name,
00035                                const std::vector<URDFName>& joint_names_in_urdf,
00036                                const URDFName& base_joint_in_urdf,
00037                                const std::string& fixed_frame,
00038                                const std::string& state_topic,
00039                                const std::string& tf_prefix)
00040 {
00041   joint_names_in_urdf_ = joint_names_in_urdf;
00042   base_joint_in_urdf_  = base_joint_in_urdf;
00043   rviz_fixed_frame_   = fixed_frame;
00044   tf_prefix_ = tf_prefix;
00045 
00046   ::ros::NodeHandle nh;
00047   state_sub_des_ = nh.subscribe(state_topic, 1, &UrdfVisualizer::StateCallback, this);
00048   ROS_DEBUG("Subscribed to: %s", state_sub_des_.getTopic().c_str());
00049 
00050   
00051   KDL::Tree my_kdl_tree;
00052   urdf::Model my_urdf_model;
00053   bool model_ok  = my_urdf_model.initParam(urdf_name);
00054   if(!model_ok)
00055   {
00056     ROS_ERROR("Invalid URDF File");
00057     exit(EXIT_FAILURE);
00058   }
00059   ROS_DEBUG("URDF successfully parsed");
00060   kdl_parser::treeFromUrdfModel(my_urdf_model, my_kdl_tree);
00061   ROS_DEBUG("Robot tree is ready");
00062 
00063   robot_publisher = std::make_shared<robot_state_publisher::RobotStatePublisher>(my_kdl_tree);
00064 }
00065 
00066 void
00067 UrdfVisualizer::StateCallback(const xpp_msgs::RobotStateJoint& msg)
00068 {
00069   auto joint_positions = AssignAngleToURDFJointName(msg.joint_state);
00070   auto W_X_B_message   = GetBaseFromRos(::ros::Time::now(), msg.base.pose);
00071 
00072   tf_broadcaster_.sendTransform(W_X_B_message);
00073   robot_publisher->publishTransforms(joint_positions, ::ros::Time::now(), tf_prefix_);
00074   robot_publisher->publishFixedTransforms(tf_prefix_);
00075 }
00076 
00077 UrdfVisualizer::UrdfnameToJointAngle
00078 UrdfVisualizer::AssignAngleToURDFJointName(const sensor_msgs::JointState &msg) const
00079 {
00080   UrdfnameToJointAngle q;
00081 
00082   for (int i=0; i<msg.position.size(); ++i)
00083     q[joint_names_in_urdf_.at(i)] = msg.position.at(i);
00084 
00085   return q;
00086 }
00087 
00088 geometry_msgs::TransformStamped
00089 UrdfVisualizer::GetBaseFromRos(const ::ros::Time& stamp,
00090                                const geometry_msgs::Pose &msg) const
00091 {
00092   
00093   geometry_msgs::TransformStamped W_X_B_message;
00094   W_X_B_message.header.stamp    = stamp;
00095   W_X_B_message.header.frame_id = rviz_fixed_frame_;
00096   W_X_B_message.child_frame_id  = tf_prefix_ + "/" + base_joint_in_urdf_;
00097 
00098   W_X_B_message.transform.translation.x =  msg.position.x;
00099   W_X_B_message.transform.translation.y =  msg.position.y;
00100   W_X_B_message.transform.translation.z =  msg.position.z;
00101 
00102   W_X_B_message.transform.rotation.w = msg.orientation.w;
00103   W_X_B_message.transform.rotation.x = msg.orientation.x;
00104   W_X_B_message.transform.rotation.y = msg.orientation.y;
00105   W_X_B_message.transform.rotation.z = msg.orientation.z;
00106 
00107   return W_X_B_message;
00108 }
00109 
00110 }