main.cpp
Go to the documentation of this file.
00001 #include <ros/ros.h>
00002 #include <sensor_msgs/NavSatFix.h>
00003 
00004 int start_rtkrcv(int argc, char **argv);
00005 void stop_rtkrcv();
00006 char get_solution(double &lat, double &lon, double &height);
00007 
00008 int
00009 main(int argc, char** argv)
00010 {
00011   std::string frame_id;
00012   ros::init(argc, argv, "rtklib");
00013 
00014   ros::NodeHandle private_nh("~");
00015   private_nh.param("frame_id", frame_id, std::string("antenna"));
00016 
00017   ros::NodeHandle nh;
00018   ros::Publisher pub = nh.advertise<sensor_msgs::NavSatFix>("fix", 5);
00019 
00020   if (!start_rtkrcv(argc, argv)) return(-1);
00021 
00022   ros::Rate r(1); // 1 Hz
00023   while (ros::ok()) {
00024     sensor_msgs::NavSatFix fix;
00025     fix.header.stamp = ros::Time::now();
00026     fix.header.frame_id = frame_id;
00027     fix.status.service = fix.status.SERVICE_GPS | fix.status.SERVICE_GALILEO;
00028     fix.status.status = get_solution(fix.latitude, fix.longitude, fix.altitude);
00029     fix.position_covariance_type = fix.COVARIANCE_TYPE_UNKNOWN;
00030     pub.publish(fix);
00031 
00032     ros::spinOnce();
00033     r.sleep();
00034   }
00035 
00036   stop_rtkrcv();
00037 
00038   return(0);
00039 }
00040 


rtkrcv
Author(s): Manuel Stahl
autogenerated on Mon Oct 6 2014 00:14:21