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/GeoUtilities.hpp>
00038
00039 #include <nav_msgs/Odometry.h>
00040 #include <sensor_msgs/NavSatFix.h>
00041 #include <tf/transform_listener.h>
00042 #include <tf/transform_broadcaster.h>
00043 #include <ros/ros.h>
00044
00045 struct GPSSim
00046 {
00047 GPSSim():
00048 rate(10),
00049 gps_z(0)
00050 {
00051 ros::NodeHandle nh,ph("~");
00052 ph.param("gps_pub",rate,rate);
00053 ph.param("gps_height",gps_z,gps_z);
00054
00055 odom = nh.subscribe<nav_msgs::Odometry>("meas_odom",1,&GPSSim::onOdom, this);
00056 gps_pub = nh.advertise<sensor_msgs::NavSatFix>("fix",1);
00057 }
00058
00059 void onOdom(const typename nav_msgs::Odometry::ConstPtr& msg)
00060 {
00061 sensor_msgs::NavSatFix::Ptr fix(new sensor_msgs::NavSatFix());
00062 fix->header.stamp = ros::Time::now();
00063 fix->header.frame_id = "worldLatLon";
00064
00065
00066 tf::Transform transform;
00067 transform.setOrigin(tf::Vector3(0, 0, -gps_z));
00068 transform.setRotation(tf::createQuaternionFromRPY(0,0,0));
00069 broadcaster.sendTransform(
00070 tf::StampedTransform(transform, ros::Time::now(),
00071 "base_link", "gps_frame"));
00072
00073 tf::StampedTransform transformLocal, transformDeg;
00074 try
00075 {
00076
00077 listener.lookupTransform("local", "gps_frame",
00078 ros::Time(0), transformLocal);
00079
00080 listener.waitForTransform("/worldLatLon", "/world",
00081 ros::Time(0), ros::Duration(5.0));
00082 listener.lookupTransform("/worldLatLon", "/world",
00083 ros::Time(0), transformDeg);
00084 double originLat = transformDeg.getOrigin().y();
00085 double originLon = transformDeg.getOrigin().x();
00086
00087 fix->altitude = -transformLocal.getOrigin().z();
00088 std::pair<double, double> diffAngle =
00089 labust::tools::meter2deg(msg->pose.pose.position.x,
00090 msg->pose.pose.position.y,
00091
00092 originLat);
00093
00094 fix->latitude = originLat + diffAngle.first;
00095 fix->longitude = originLon + diffAngle.second;
00096
00097 static int i=0;
00098 i=++i%rate;
00099 if (fix->altitude>=-0.1 && (i == 0))
00100 {
00101 gps_pub.publish(fix);
00102 }
00103 }
00104 catch (tf::TransformException& ex)
00105 {
00106 ROS_WARN("%s",ex.what());
00107 }
00108 }
00109
00110 private:
00111 ros::Subscriber odom;
00112 ros::Publisher gps_pub;
00113 int rate;
00114 tf::TransformListener listener;
00115 tf::TransformBroadcaster broadcaster;
00116 double gps_z;
00117 };
00118
00119 int main(int argc, char* argv[])
00120 {
00121 ros::init(argc,argv,"gps_sim");
00122 ros::NodeHandle nh;
00123 GPSSim gps;
00124 ros::spin();
00125 return 0;
00126 }
00127
00128