from_fix.cpp
Go to the documentation of this file.
00001 
00046 #include "ros/ros.h"
00047 #include "sensor_msgs/NavSatFix.h"
00048 #include "nav_msgs/Odometry.h"
00049 
00050 #include <boost/bind.hpp>
00051 
00052 extern "C" {
00053   // The backend of this node is an included C library called libswiftnav.
00054   #include "coord_system.h"
00055 }
00056 
00057 #define TO_RADIANS (M_PI/180)
00058 #define TO_DEGREES (180/M_PI)
00059 
00060 void initialize_datum(double datum_ecef[3],
00061                       const sensor_msgs::NavSatFixConstPtr fix_ptr,
00062                       const ros::Publisher& pub_datum)
00063 {
00064   ros::NodeHandle pnh("~");
00065   sensor_msgs::NavSatFix datum_msg(*fix_ptr);
00066 
00067   // Local ENU coordinates are with respect to a plane which is 
00068   // perpendicular to a particular lat/lon. This logic decides 
00069   // whether to use a specific passed-in point (typical for 
00070   // repeated tests in a locality) or just an arbitrary starting
00071   // point (more ad-hoc type scenarios).
00072   if (pnh.hasParam("datum_latitude") &&
00073       pnh.hasParam("datum_longitude") && 
00074       pnh.hasParam("datum_altitude")) {
00075     pnh.getParam("datum_latitude", datum_msg.latitude);  
00076     pnh.getParam("datum_longitude", datum_msg.longitude);  
00077     pnh.getParam("datum_altitude", datum_msg.altitude);  
00078     ROS_INFO("Using datum provided by node parameters.");
00079   } else {
00080     ROS_INFO("Using initial position fix as datum.");
00081   }
00082   pub_datum.publish(datum_msg);
00083 
00084   // The datum point is stored as an ECEF, for mathematical reasons.
00085   // We convert it here, using the appropriate function from
00086   // libswiftnav.
00087   double llh[3] = { datum_msg.latitude * TO_RADIANS,
00088                     datum_msg.longitude * TO_RADIANS,
00089                     datum_msg.altitude };
00090   wgsllh2ecef(llh, datum_ecef);
00091 }
00092 
00093 
00094 static void handle_fix(const sensor_msgs::NavSatFixConstPtr fix_ptr,
00095                        const ros::Publisher& pub_enu,
00096                        const ros::Publisher& pub_datum,
00097                        const std::string& output_tf_frame,
00098                        const double invalid_covariance_value)
00099 {
00100   static double ecef_datum[3];
00101   static bool have_datum = false;
00102 
00103   if (!have_datum) {
00104     initialize_datum(ecef_datum, fix_ptr, pub_datum);
00105     have_datum = true;
00106   }
00107 
00108   // Prepare the appropriate input vector to convert the input latlon
00109   // to an ECEF triplet.
00110   double llh[3] = { fix_ptr->latitude * TO_RADIANS,
00111                     fix_ptr->longitude * TO_RADIANS,
00112                     fix_ptr->altitude };
00113   double ecef[3];
00114   wgsllh2ecef(llh, ecef);
00115   
00116   // ECEF triplet is converted to north-east-down (NED), by combining it
00117   // with the ECEF-formatted datum point.
00118   double ned[3];
00119   wgsecef2ned_d(ecef, ecef_datum, ned);
00120 
00121   nav_msgs::Odometry odom_msg;
00122   odom_msg.header.stamp = fix_ptr->header.stamp;
00123   odom_msg.header.frame_id = output_tf_frame; // Name of output tf frame
00124   odom_msg.child_frame_id = fix_ptr->header.frame_id; // Antenna location
00125   odom_msg.pose.pose.position.x = ned[1];
00126   odom_msg.pose.pose.position.y = ned[0];
00127   odom_msg.pose.pose.position.z = -ned[2];
00128 
00129   // We only need to populate the diagonals of the covariance matrix; the
00130   // rest initialize to zero automatically, which is correct as the
00131   // dimensions of the state are independent.
00132   odom_msg.pose.covariance[0] = fix_ptr->position_covariance[0];
00133   odom_msg.pose.covariance[7] = fix_ptr->position_covariance[4];
00134   odom_msg.pose.covariance[14] = fix_ptr->position_covariance[8];
00135   
00136   // Do not use orientation dimensions from GPS.
00137   // (-1 is an invalid covariance and standard ROS practice to set as invalid.)
00138   odom_msg.pose.covariance[21] = invalid_covariance_value;
00139   odom_msg.pose.covariance[28] = invalid_covariance_value;
00140   odom_msg.pose.covariance[35] = invalid_covariance_value;
00141 
00142   pub_enu.publish(odom_msg); 
00143 }
00144 
00145 
00146 int main(int argc, char **argv)
00147 {
00148   ros::init(argc, argv, "from_fix");
00149   ros::NodeHandle n;
00150   ros::NodeHandle pnh("~");
00151 
00152   std::string output_tf_frame;
00153   pnh.param<std::string>("output_frame_id", output_tf_frame, "map");
00154   double invalid_covariance_value;
00155   pnh.param<double>("invalid_covariance_value", invalid_covariance_value, -1.0); // -1 is ROS convention.  1e6 is robot_pose_ekf convention
00156 
00157   // Initialize publishers, and pass them into the handler for 
00158   // the subscriber.
00159   ros::Publisher pub_enu = n.advertise<nav_msgs::Odometry>("enu", 5);
00160   ros::Publisher pub_datum = n.advertise<sensor_msgs::NavSatFix>("enu_datum", 5, true);
00161   ros::Subscriber sub = n.subscribe<sensor_msgs::NavSatFix>("fix", 5, 
00162       boost::bind(handle_fix, _1, pub_enu, pub_datum, output_tf_frame, invalid_covariance_value));
00163 
00164   ros::spin();
00165   return 0;
00166 }
00167 


enu
Author(s): Mike Purvis
autogenerated on Sun Oct 5 2014 23:44:53