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 <tf/transform_listener.h>
00041 #include <tf/transform_broadcaster.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 tf::Transform transform;
00086 if (fixValidated)
00087 {
00088 transform.setOrigin(tf::Vector3(originLon, originLat, 0));
00089 transform.setRotation(tf::createQuaternionFromRPY(0,0,0));
00090 broadcaster.sendTransform(tf::StampedTransform(transform, ros::Time::now(), "/worldLatLon", "/world"));
00091 }
00092
00093 transform.setOrigin(tf::Vector3(0, 0, 0));
00094 Eigen::Quaternion<float> q;
00095 labust::tools::quaternionFromEulerZYX(M_PI,0,M_PI/2,q);
00096 transform.setRotation(tf::Quaternion(q.x(),q.y(),q.z(),q.w()));
00097 broadcaster.sendTransform(tf::StampedTransform(transform, ros::Time::now(), "/world", "local"));
00098
00099 rate.sleep();
00100 }
00101 }
00102
00103 private:
00104 ros::Subscriber gps_raw;
00105 tf::TransformBroadcaster broadcaster;
00106 double originLat, originLon;
00107 bool fixValidated;
00108 int fixCount;
00109 boost::thread runner;
00110 };
00111
00112 int main(int argc, char* argv[])
00113 {
00114 ros::init(argc,argv,"llnode");
00115 ros::NodeHandle nh;
00116 LLNode llnode;
00117 ros::spin();
00118 return 0;
00119 }
00120
00121