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 #ifndef _atlascar_transforms_CPP_
00028 #define _atlascar_transforms_CPP_
00029 
00038 #include <boost/algorithm/string.hpp>
00039 #include <string>
00040 #include <ros/ros.h>
00041 #include <sensor_msgs/JointState.h>
00042 #include <tf/transform_broadcaster.h>
00043 #include <visualization_msgs/Marker.h>
00044 #include <visualization_msgs/MarkerArray.h>
00045 #include <tf/transform_listener.h>
00046 #include <pcl_ros/transforms.h>
00047 #include <pcl/ros/conversions.h>
00048 #include <pcl/point_cloud.h>
00049 #include <pcl/point_types.h>
00050 #include <interactive_markers/interactive_marker_server.h>
00051 #include <interactive_markers/menu_handler.h>
00052 #include <ros/package.h>
00053 #include <libxml/encoding.h>
00054 #include <libxml/xmlwriter.h>
00055 #include <libxml/tree.h>
00056 #include <libxml/parser.h>
00057 #include <libxml/xpath.h>
00058 #include <libxml/xpathInternals.h>
00059 #include <libxml/xmlreader.h>
00060 
00061 
00062 #define PFLN {printf("FILE %s LINE %d\n",__FILE__, __LINE__);}
00063 
00064 using namespace ros;
00065 using namespace std;
00066 using namespace boost;
00067 using namespace visualization_msgs;
00068 
00069 tf::TransformListener *p_listener;
00070 boost::shared_ptr<interactive_markers::InteractiveMarkerServer> server;
00071 float marker_pos = 0;
00072 
00073 typedef struct
00074 {
00075         double x,y,z;
00076         std::string name;
00077 }t_reference_frame;
00078 
00079 std::vector<boost::shared_ptr <t_reference_frame> > v_rf;
00080 
00081 int get_i_from_name(std::vector<boost::shared_ptr <t_reference_frame> >* v_rf, std::string name)
00082 {
00083         int ret=-1; 
00084         for (size_t i=0; i<v_rf->size(); ++i)
00085         {
00086                 if (name == (*v_rf)[i]->name)
00087                 {
00088                         ret=i;
00089                         break;
00090                 }       
00091         }
00092 
00093         return ret;
00094 }
00095 
00096 Marker makeBox( InteractiveMarker &msg )
00097 {
00098         Marker marker;
00099 
00100         marker.type = Marker::SPHERE;
00101         marker.scale.x = msg.scale * 0.05;
00102         marker.scale.y = msg.scale * 0.05;
00103         marker.scale.z = msg.scale * 0.05;
00104         marker.color.r = 0;
00105         marker.color.g = 0.7;
00106         marker.color.b = 0;
00107         marker.color.a = 0.0;
00108 
00109         return marker;
00110 }
00111 void processFeedback( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback )
00112 {
00113         switch ( feedback->event_type )
00114         {
00115                 case visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE:
00116                         printf("you are moving marker %s\n",feedback->marker_name.c_str());
00117 
00118 
00119                         int ret = get_i_from_name(&v_rf, feedback->marker_name);
00120 
00121                         printf("ret=%d\n",ret);
00122 
00123                         v_rf[ret]->x = feedback->pose.position.x;
00124                         v_rf[ret]->y = feedback->pose.position.y;
00125                         v_rf[ret]->z = feedback->pose.position.z;
00126                         break;
00127         }
00128 
00129         server->applyChanges();
00130 }
00131 
00132 InteractiveMarkerControl& makeBoxControl( InteractiveMarker &msg )
00133 {
00134         InteractiveMarkerControl control;
00135         control.always_visible = true;
00136         control.markers.push_back( makeBox(msg) );
00137         msg.controls.push_back( control );
00138         return msg.controls.back();
00139 }
00140 
00141 void set_label_pos(double x, double y, double z, visualization_msgs::Marker* msg, std::vector<visualization_msgs::Marker>* marker_vec)
00142 {
00143         
00144         
00145         
00146                 
00147         
00148         
00149         
00150                 
00151         
00152 
00153 
00154         
00155         
00156         
00157         
00158 
00159         
00160         
00161 
00162         geometry_msgs::Point pt;
00163         visualization_msgs::Marker lmsg; 
00164         lmsg.pose.orientation.w = 1.0;
00165         lmsg.header.stamp = ros::Time::now();
00166         lmsg.id = 0;
00167         lmsg.scale.x = 0.02; lmsg.scale.y = 1; lmsg.scale.z = 0.095; 
00168         lmsg.color.r = 0.0; lmsg.color.g = 0; lmsg.color.b = 0.0; lmsg.color.a = 0.4;
00169         lmsg.pose.position.x = 0; lmsg.pose.position.y = 0; lmsg.pose.position.z = 0; 
00170         lmsg.action = visualization_msgs::Marker::ADD;
00171         lmsg.type = visualization_msgs::Marker::LINE_STRIP;
00172 
00173         lmsg.header.frame_id = msg->header.frame_id;
00174         lmsg.ns = "CNT " + msg->header.frame_id;
00175 
00176         pt.x=0; pt.y=0; pt.z=0; 
00177         lmsg.points.push_back(pt);
00178         
00179         pt.x=x; pt.y=y; pt.z=z;
00180         lmsg.points.push_back(pt);
00181         marker_vec->push_back(lmsg);
00182 
00183 
00184         
00185         msg->pose.position.x = x; msg->pose.position.y = y; msg->pose.position.z = z; 
00186 }
00187 
00188 
00189 
00190 
00191 int add_to_viz_markers_vec(std::vector<visualization_msgs::Marker>* marker_vec)
00192 {
00193         geometry_msgs::Point p;
00194         std_msgs::ColorRGBA color;
00195 
00196         
00197         visualization_msgs::Marker msg; 
00198         msg.pose.orientation.w = 1.0;
00199         msg.header.stamp = ros::Time::now();
00200         msg.id = 0;
00201         msg.scale.x = 1; msg.scale.y = 1; msg.scale.z = 0.1; 
00202         msg.color.r = 0.0; msg.color.g = 0; msg.color.b = 0.3; msg.color.a = 1;
00203         msg.pose.position.x = 0; msg.pose.position.y = 0; msg.pose.position.z = -0.1; 
00204         msg.action = visualization_msgs::Marker::ADD;
00205         msg.type = visualization_msgs::Marker::TEXT_VIEW_FACING;
00206 
00207         for (size_t i=0; i< v_rf.size(); ++i)
00208         {
00209                 msg.header.frame_id = v_rf[i]->name;
00210                 msg.ns = msg.header.frame_id.c_str();
00211                 msg.text = msg.header.frame_id.c_str(); 
00212                 set_label_pos(v_rf[i]->x,v_rf[i]->y,v_rf[i]->z, &msg, marker_vec);
00213                 marker_vec->push_back(msg);
00214         }
00215 
00216         return 1;
00217 }
00218 
00219 void make6DofMarker( bool fixed, std::string name , double x, double y, double z)
00220 {
00221         InteractiveMarker int_marker;
00222         int_marker.header.frame_id = name;
00223         int_marker.pose.position.x = x;
00224         int_marker.pose.position.y = y;
00225         int_marker.pose.position.z = z;
00226         int_marker.scale = 0.1;
00227 
00228         int_marker.name = name;
00229         int_marker.description = "";
00230 
00231         
00232         makeBoxControl(int_marker);
00233         InteractiveMarkerControl control;
00234 
00235         control.orientation.w = 1;
00236         control.orientation.x = 1;
00237         control.orientation.y = 0;
00238         control.orientation.z = 0;
00239         control.name = "move_x";
00240         control.interaction_mode = InteractiveMarkerControl::MOVE_AXIS;
00241         int_marker.controls.push_back(control);
00242 
00243         control.orientation.w = 1;
00244         control.orientation.x = 0;
00245         control.orientation.y = 1;
00246         control.orientation.z = 0;
00247         control.name = "move_z";
00248         control.interaction_mode = InteractiveMarkerControl::MOVE_AXIS;
00249         int_marker.controls.push_back(control);
00250 
00251         control.orientation.w = 1;
00252         control.orientation.x = 0;
00253         control.orientation.y = 0;
00254         control.orientation.z = 1;
00255         control.name = "move_y";
00256         control.interaction_mode = InteractiveMarkerControl::MOVE_AXIS;
00257         int_marker.controls.push_back(control);
00258 
00259         server->insert(int_marker);
00260         server->setCallback(int_marker.name, &processFeedback);
00261 }
00262 
00270 void GetName(xmlTextReaderPtr reader,string& str)
00271 {
00272         xmlChar*name=xmlTextReaderName(reader);
00273         if(!name)return;
00274         str=(char*)name;
00275         xmlFree(name);
00276 }
00277 
00285 void GetValue(xmlTextReaderPtr reader,string& str)
00286 {
00287         xmlChar*value=xmlTextReaderValue(reader);
00288         if(!value)return;
00289         str=(char*)value;
00290         xmlFree(value);
00291 }
00292 
00301 void GetAttribute(xmlTextReaderPtr reader,const xmlChar*name,string& str)
00302 {
00303         xmlChar*attribute=xmlTextReaderGetAttribute(reader,name);
00304         if(!attribute)return;
00305         str=(char*)attribute;
00306         xmlFree(attribute);
00307 }
00308 
00309 void NodeHandler(xmlTextReaderPtr reader)
00310 {
00311         string name,value;
00312         string dev_name;
00313         GetName(reader,name);
00314         
00315         to_upper(name);
00316         
00317         if(name=="LINK" && xmlTextReaderNodeType(reader)==1)
00318         {
00319                 GetAttribute(reader,BAD_CAST "name",dev_name);
00320                 boost::shared_ptr<t_reference_frame> rf(new t_reference_frame);
00321                 rf->name = dev_name;
00322                 rf->x = 0; rf->y =0; rf->z =0;
00323                 v_rf.push_back(rf);
00324                 make6DofMarker( true, v_rf[v_rf.size()-1]->name , v_rf[v_rf.size()-1]->x, v_rf[v_rf.size()-1]->y, v_rf[v_rf.size()-1]->z);
00325         }
00326 }
00327 
00328 int main(int argc, char **argv)
00329 {
00330         ros::init(argc, argv, "atlascar_transforms"); 
00331         ros::NodeHandle n; 
00332         ros::Rate loop_rate(1); 
00333         ros::Publisher vis_pub = n.advertise<visualization_msgs::MarkerArray>( "/axis_markers", 0 );
00334         tf::TransformListener listener(n,ros::Duration(10));
00335         p_listener=&listener;
00336         server.reset( new interactive_markers::InteractiveMarkerServer("show_axes","",false) );
00337         ros::Duration(0.1).sleep();
00338 
00339 
00340 
00341         
00342         
00343 
00344         std::string urdf_file = ros::package::getPath("coordinate_frames") + "/urdf/urdf.xml";
00345 
00346         printf("reading %s\n",urdf_file.c_str());
00347 
00348         int ret;
00349         xmlTextReaderPtr reader = xmlNewTextReaderFilename(urdf_file.c_str());
00350         if(reader!=NULL)
00351         {
00352                 do
00353                 {
00354                         ret=xmlTextReaderRead(reader);
00355                         NodeHandler(reader);
00356                 }while(ret==1);
00357                 
00358                 xmlFreeTextReader(reader);
00359                 if (ret != 0)
00360                 {
00361                         ROS_ERROR("Failed to parse file");
00362                         return -1;
00363                 }
00364         }else
00365         {
00366                 ROS_ERROR("Failed to parse file");
00367                 return -1;
00368         }
00369 
00370         PFLN
00371 
00372 
00373 
00374 
00375 
00376         server->applyChanges();
00377 
00378 
00379         while (ros::ok())
00380         {
00381                 visualization_msgs::MarkerArray marker_msg;
00382                 
00383                 add_to_viz_markers_vec(&(marker_msg.markers));
00384 
00385                 vis_pub.publish(marker_msg);
00386 
00387                 
00388                 loop_rate.sleep();
00389                 ros::spinOnce();
00390                 ros::spinOnce();
00391                 ros::spinOnce();
00392                 ros::spinOnce();
00393                 ros::spinOnce();
00394                 ros::spinOnce();
00395         }
00396 
00397 
00398         server.reset();
00399 }
00400 #endif