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 <rve_common_transformers/urdf.h>
00031 #include <rve_transformer/transformer_manager.h>
00032 #include <rve_transformer/frame_manager.h>
00033 #include <rve_properties/property_node.h>
00034 #include <rve_properties/messages.h>
00035 #include <rve_render_client/urdf.h>
00036
00037 #include <tf2/exceptions.h>
00038
00039 #include <urdf/model.h>
00040
00041 #include <rve_msgs/make_vector3.h>
00042 #include <rve_msgs/make_quaternion.h>
00043 #include <rve_common/eigen_conversions.h>
00044 #include <geometry_msgs/TransformStamped.h>
00045
00046 namespace rve_common_transformers
00047 {
00048
00049 URDF::URDF()
00050 {
00051 }
00052
00053 URDF::~URDF()
00054 {
00055 getPropertyNode()->removeChangeCallback(this);
00056 }
00057
00058 void URDF::onInit()
00059 {
00060
00061
00062 urdf::Model m;
00063 m.initParam("robot_description");
00064 urdf_ = addObject(rve_render_client::createURDF(m));
00065 }
00066
00067 void URDF::onUpdate()
00068 {
00069 rve_transformer::FrameManagerPtr frame_manager = getManager()->getFrameManager();
00070 rve_render_client::URDF::LinkIterator it = urdf_->linksBegin();
00071 rve_render_client::URDF::LinkIterator end = urdf_->linksEnd();
00072 for (; it != end; ++it)
00073 {
00074 const rve_render_client::URDFLinkPtr& link = *it;
00075 const std::string link_name = link->getName();
00076
00077 try
00078 {
00079 geometry_msgs::TransformStamped transform = frame_manager->lookupTransform(link_name, ros::Time());
00080 const geometry_msgs::Vector3& v = transform.transform.translation;
00081 const geometry_msgs::Quaternion& q = transform.transform.rotation;
00082
00083 link->setTransform(rve_msgs::makeVector3(v.x, v.y, v.z), rve_msgs::makeQuaternion(q.x, q.y, q.z, q.w));
00084 }
00085 catch (tf2::TransformException& e)
00086 {
00087 ROS_ERROR("TransformException: %s", e.what());
00088 }
00089 }
00090 }
00091
00092 void URDF::onPropertyChanged(const rve_properties::PropertyNodePtr& node, const std::string& path, rve_properties::PropertyChangeType type)
00093 {
00094 if (type != rve_properties::PropertyChanged)
00095 {
00096 return;
00097 }
00098
00099 }
00100
00101 }
00102