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 #include <labust/tools/GeoUtilities.hpp>
00039 
00040 #include <sensor_msgs/NavSatFix.h>
00041 #include <tf2_ros/static_transform_broadcaster.h>
00042 #include <geometry_msgs/TransformStamped.h>
00043 #include <ros/ros.h>
00044 
00045 #include <boost/thread.hpp>
00046 
00047 struct LTPNode
00048 {
00049         enum {NEEDED_FIXES=30};
00050 
00051         LTPNode():
00052                 origin_lat(0),
00053                 origin_lon(0),
00054                 fix_valid(false),
00055                 fix_count(0)
00056         {
00057                 ros::NodeHandle nh,ph("~");
00058                 nh.param("environment/origin_lat", origin_lat, origin_lat);
00059                 ph.param("origin_lat", origin_lat, origin_lat);
00060                 nh.param("environment/origin_lon", origin_lon, origin_lon);
00061                 ph.param("origin_lon", origin_lon, origin_lon);
00062                 ph.param("use_local_fix",fix_valid, fix_valid);
00063                 ph.param("use_local_fix",fix_valid, fix_valid);
00064 
00065                 gps_raw = nh.subscribe<sensor_msgs::NavSatFix>("gps",1,<PNode::onGps, this);
00066 
00067                 if (fix_valid) this->setupFrame();
00068 
00069                 
00070         }
00071 
00072         ~LTPNode()
00073         {
00074                 runner.join();
00075         }
00076 
00077         void onGps(const sensor_msgs::NavSatFix::ConstPtr& fix)
00078         {
00079                 if (!fix_valid)
00080                 {
00081                         if (++fix_count > NEEDED_FIXES)
00082                         {
00083                                 origin_lat = fix->latitude;
00084                                 origin_lon = fix->longitude;
00085                                 fix_valid = true;
00086                                 fix_count = 0;
00087                                 this->setupFrame();
00088                         }
00089                 }
00090         };
00091 
00092         void setupFrame()
00093         {
00094                 Eigen::Vector3d geo;
00095                 geo<<origin_lon, origin_lat, 0;
00096                 Eigen::Vector3d ecef = labust::tools::geodetic2ecef(geo);
00097                 Eigen::Matrix3d nedrot = labust::tools::nedrot(geo);
00098                 Eigen::Quaternion<double> q(nedrot.transpose());
00099 
00100                 geometry_msgs::TransformStamped transform;
00101                 transform.transform.translation.x = ecef(0);
00102                 transform.transform.translation.y = ecef(1);
00103                 transform.transform.translation.z = ecef(2);
00104                 transform.transform.rotation.x = q.x();
00105                 transform.transform.rotation.y = q.y();
00106                 transform.transform.rotation.z = q.z();
00107                 transform.transform.rotation.w = q.w();
00108                 transform.child_frame_id = "local";
00109                 transform.header.frame_id = "ecef";
00110                 transform.header.stamp = ros::Time::now();
00111                 broadcaster.sendTransform(transform);
00112         }
00113 
00114 private:
00116         ros::Subscriber gps_raw;
00118         tf2_ros::StaticTransformBroadcaster broadcaster;
00120         double origin_lat;
00122         double origin_lon;
00124         bool fix_valid;
00126         int fix_count;
00128         boost::thread runner;
00129 };
00130 
00131 int main(int argc, char* argv[])
00132 {
00133         ros::init(argc,argv,"ltp_node");
00134         LTPNode llnode;
00135         ros::spin();
00136         return 0;
00137 }
00138 
00139