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 
00031 
00032 
00033 
00034 
00035 
00036 
00037 #include <labust/tools/conversions.hpp>
00038 
00039 #include <sensor_msgs/NavSatFix.h>
00040 #include <tf2_ros/transform_broadcaster.h>
00041 #include <geometry_msgs/TransformStamped.h>
00042 #include <ros/ros.h>
00043 
00044 #include <boost/thread.hpp>
00045 
00046 struct LLNode
00047 {
00048         LLNode():
00049                 originLat(0),
00050                 originLon(0),
00051                 fixValidated(false),
00052                 fixCount(0)
00053         {
00054                 ros::NodeHandle nh,ph("~");
00055                 nh.param("LocalOriginLat",originLat,originLat);
00056                 nh.param("LocalOriginLon",originLon,originLon);
00057                 ph.param("LocalFixSim",fixValidated, fixValidated);
00058 
00059                 gps_raw = nh.subscribe<sensor_msgs::NavSatFix>("gps",1,&LLNode::onGps, this);
00060 
00061                 runner = boost::thread(boost::bind(&LLNode::publishFrame, this));
00062         }
00063 
00064         ~LLNode()
00065         {
00066                 runner.join();
00067         }
00068 
00069         void onGps(const sensor_msgs::NavSatFix::ConstPtr& fix)
00070         {
00071                 
00072                 if (!fixValidated)
00073                 {
00074                         originLat = fix->latitude;
00075                         originLon = fix->longitude;
00076                         fixValidated = true;
00077                 }
00078         };
00079 
00080         void publishFrame()
00081         {
00082                 ros::Rate rate(1);
00083                 while (ros::ok())
00084                 {
00085                         geometry_msgs::TransformStamped transform;
00086                         if (fixValidated)
00087                         {
00088                                 geometry_msgs::TransformStamped transform;
00089                                 transform.transform.translation.x = originLon;
00090                                 transform.transform.translation.y = originLat;
00091                                 transform.transform.translation.z = 0;
00092                                 labust::tools::quaternionFromEulerZYX(0, 0, 0,
00093                                                 transform.transform.rotation);
00094                                 transform.child_frame_id = "world";
00095                                 transform.header.frame_id = "worldLatLon";
00096                                 transform.header.stamp = ros::Time::now();
00097                                 broadcaster.sendTransform(transform);
00098                         }
00099 
00100                         transform.transform.translation.x = 0;
00101                         transform.transform.translation.y = 0;
00102                         transform.transform.translation.z = 0;
00103                         Eigen::Quaternion<float> q;
00104                         labust::tools::quaternionFromEulerZYX(M_PI,0,M_PI/2,transform.transform.rotation);
00105                         transform.child_frame_id = "local";
00106                         transform.header.frame_id = "world";
00107                         transform.header.stamp = ros::Time::now();
00108                         broadcaster.sendTransform(transform);
00109 
00110                         rate.sleep();
00111                 }
00112         }
00113 
00114 private:
00115         ros::Subscriber gps_raw;
00116         tf2_ros::TransformBroadcaster broadcaster;
00117         double originLat, originLon;
00118         bool fixValidated;
00119         int fixCount;
00120         boost::thread runner;
00121 };
00122 
00123 int main(int argc, char* argv[])
00124 {
00125         ros::init(argc,argv,"llnode");
00126         ros::NodeHandle nh;
00127         LLNode llnode;
00128         ros::spin();
00129         return 0;
00130 }
00131 
00132