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