client.cpp
Go to the documentation of this file.
00001 #include <ros/ros.h>
00002 #include <gps_common/GPSFix.h>
00003 #include <gps_common/GPSStatus.h>
00004 #include <sensor_msgs/NavSatFix.h>
00005 #include <sensor_msgs/NavSatStatus.h>
00006 #include <libgpsmm.h>
00007 
00008 #include <cmath>
00009 
00010 using namespace gps_common;
00011 using namespace sensor_msgs;
00012 
00013 class GPSDClient {
00014   public:
00015     GPSDClient() : privnode("~"), gps(NULL), use_gps_time(true), check_fix_by_variance(true), frame_id("gps") {}
00016 
00017     bool start() {
00018       gps_fix_pub = node.advertise<GPSFix>("extended_fix", 1);
00019       navsat_fix_pub = node.advertise<NavSatFix>("fix", 1);
00020 
00021       privnode.getParam("use_gps_time", use_gps_time);
00022       privnode.getParam("check_fix_by_variance", check_fix_by_variance);
00023       privnode.param("frame_id", frame_id, frame_id);
00024 
00025       std::string host = "localhost";
00026       int port = 2947;
00027       privnode.getParam("host", host);
00028       privnode.getParam("port", port);
00029 
00030       char port_s[12];
00031       snprintf(port_s, 12, "%d", port);
00032 
00033       gps_data_t *resp = NULL;
00034 
00035 #if GPSD_API_MAJOR_VERSION >= 5
00036       gps = new gpsmm(host.c_str(), port_s);
00037       resp = gps->stream(WATCH_ENABLE);
00038 #elif GPSD_API_MAJOR_VERSION == 4
00039       gps = new gpsmm();
00040       gps->open(host.c_str(), port_s);
00041       resp = gps->stream(WATCH_ENABLE);
00042 #else
00043       gps = new gpsmm();
00044       resp = gps->open(host.c_str(), port_s);
00045       gps->query("w\n");
00046 #endif
00047 
00048       if (resp == NULL) {
00049         ROS_ERROR("Failed to open GPSd");
00050         return false;
00051       }
00052 
00053       ROS_INFO("GPSd opened");
00054       return true;
00055     }
00056 
00057     void step() {
00058 #if GPSD_API_MAJOR_VERSION >= 5
00059       if (!gps->waiting(1e6))
00060         return;
00061 
00062       gps_data_t *p = gps->read();
00063 #else
00064       gps_data_t *p = gps->poll();
00065 #endif
00066       process_data(p);
00067     }
00068 
00069     void stop() {
00070       // gpsmm doesn't have a close method? OK ...
00071     }
00072 
00073   private:
00074     ros::NodeHandle node;
00075     ros::NodeHandle privnode;
00076     ros::Publisher gps_fix_pub;
00077     ros::Publisher navsat_fix_pub;
00078     gpsmm *gps;
00079 
00080     bool use_gps_time;
00081     bool check_fix_by_variance;
00082     std::string frame_id;
00083 
00084     void process_data(struct gps_data_t* p) {
00085       if (p == NULL)
00086         return;
00087 
00088       if (!p->online)
00089         return;
00090 
00091       process_data_gps(p);
00092       process_data_navsat(p);
00093     }
00094 
00095 
00096 #if GPSD_API_MAJOR_VERSION >= 4
00097 #define SATS_VISIBLE p->satellites_visible
00098 #elif GPSD_API_MAJOR_VERSION == 3
00099 #define SATS_VISIBLE p->satellites
00100 #else
00101 #error "gpsd_client only supports gpsd API versions 3+"
00102 #endif
00103 
00104     void process_data_gps(struct gps_data_t* p) {
00105       ros::Time time = ros::Time::now();
00106 
00107       GPSFix fix;
00108       GPSStatus status;
00109 
00110       status.header.stamp = time;
00111       fix.header.stamp = time;
00112       fix.header.frame_id = frame_id;
00113 
00114       status.satellites_used = p->satellites_used;
00115 
00116       status.satellite_used_prn.resize(status.satellites_used);
00117       for (int i = 0; i < status.satellites_used; ++i) {
00118 #if GPSD_API_MAJOR_VERSION > 5
00119         status.satellite_used_prn[i] = p->skyview[i].used;
00120 #else
00121         status.satellite_used_prn[i] = p->used[i];
00122 #endif
00123       }
00124 
00125       status.satellites_visible = SATS_VISIBLE;
00126 
00127       status.satellite_visible_prn.resize(status.satellites_visible);
00128       status.satellite_visible_z.resize(status.satellites_visible);
00129       status.satellite_visible_azimuth.resize(status.satellites_visible);
00130       status.satellite_visible_snr.resize(status.satellites_visible);
00131 
00132       for (int i = 0; i < SATS_VISIBLE; ++i) {
00133 #if GPSD_API_MAJOR_VERSION > 5
00134         status.satellite_visible_prn[i] = p->skyview[i].PRN;
00135         status.satellite_visible_z[i] = p->skyview[i].elevation;
00136         status.satellite_visible_azimuth[i] = p->skyview[i].azimuth;
00137         status.satellite_visible_snr[i] = p->skyview[i].ss;
00138 #else
00139         status.satellite_visible_prn[i] = p->PRN[i];
00140         status.satellite_visible_z[i] = p->elevation[i];
00141         status.satellite_visible_azimuth[i] = p->azimuth[i];
00142         status.satellite_visible_snr[i] = p->ss[i];
00143 #endif
00144       }
00145 
00146       if ((p->status & STATUS_FIX) && !(check_fix_by_variance && std::isnan(p->fix.epx))) {
00147         status.status = 0; // FIXME: gpsmm puts its constants in the global
00148                            // namespace, so `GPSStatus::STATUS_FIX' is illegal.
00149 
00150 // STATUS_DGPS_FIX was removed in API version 6 but re-added afterward
00151 #if GPSD_API_MAJOR_VERSION != 6
00152         if (p->status & STATUS_DGPS_FIX)
00153           status.status |= 18; // same here
00154 #endif
00155 
00156         fix.time = p->fix.time;
00157         fix.latitude = p->fix.latitude;
00158         fix.longitude = p->fix.longitude;
00159         fix.altitude = p->fix.altitude;
00160         fix.track = p->fix.track;
00161         fix.speed = p->fix.speed;
00162         fix.climb = p->fix.climb;
00163 
00164 #if GPSD_API_MAJOR_VERSION > 3
00165         fix.pdop = p->dop.pdop;
00166         fix.hdop = p->dop.hdop;
00167         fix.vdop = p->dop.vdop;
00168         fix.tdop = p->dop.tdop;
00169         fix.gdop = p->dop.gdop;
00170 #else
00171         fix.pdop = p->pdop;
00172         fix.hdop = p->hdop;
00173         fix.vdop = p->vdop;
00174         fix.tdop = p->tdop;
00175         fix.gdop = p->gdop;
00176 #endif
00177 
00178         fix.err = p->epe;
00179         fix.err_vert = p->fix.epv;
00180         fix.err_track = p->fix.epd;
00181         fix.err_speed = p->fix.eps;
00182         fix.err_climb = p->fix.epc;
00183         fix.err_time = p->fix.ept;
00184 
00185         /* TODO: attitude */
00186       } else {
00187         status.status = -1; // STATUS_NO_FIX
00188       }
00189 
00190       fix.status = status;
00191 
00192       gps_fix_pub.publish(fix);
00193     }
00194 
00195     void process_data_navsat(struct gps_data_t* p) {
00196       NavSatFixPtr fix(new NavSatFix);
00197 
00198       /* TODO: Support SBAS and other GBAS. */
00199 
00200       if (use_gps_time && !std::isnan(p->fix.time))
00201         fix->header.stamp = ros::Time(p->fix.time);
00202       else
00203         fix->header.stamp = ros::Time::now();
00204 
00205       fix->header.frame_id = frame_id;
00206 
00207       /* gpsmm pollutes the global namespace with STATUS_,
00208        * so we need to use the ROS message's integer values
00209        * for status.status
00210        */
00211       switch (p->status) {
00212         case STATUS_NO_FIX:
00213           fix->status.status = -1; // NavSatStatus::STATUS_NO_FIX;
00214           break;
00215         case STATUS_FIX:
00216           fix->status.status = 0; // NavSatStatus::STATUS_FIX;
00217           break;
00218 // STATUS_DGPS_FIX was removed in API version 6 but re-added afterward
00219 #if GPSD_API_MAJOR_VERSION != 6 
00220         case STATUS_DGPS_FIX:
00221           fix->status.status = 2; // NavSatStatus::STATUS_GBAS_FIX;
00222           break;
00223 #endif
00224       }
00225 
00226       fix->status.service = NavSatStatus::SERVICE_GPS;
00227 
00228       fix->latitude = p->fix.latitude;
00229       fix->longitude = p->fix.longitude;
00230       fix->altitude = p->fix.altitude;
00231 
00232       /* gpsd reports status=OK even when there is no current fix,
00233        * as long as there has been a fix previously. Throw out these
00234        * fake results, which have NaN variance
00235        */
00236       if (std::isnan(p->fix.epx) && check_fix_by_variance) {
00237         return;
00238       }
00239 
00240       fix->position_covariance[0] = p->fix.epx;
00241       fix->position_covariance[4] = p->fix.epy;
00242       fix->position_covariance[8] = p->fix.epv;
00243 
00244       fix->position_covariance_type = NavSatFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
00245 
00246       navsat_fix_pub.publish(fix);
00247     }
00248 };
00249 
00250 int main(int argc, char ** argv) {
00251   ros::init(argc, argv, "gpsd_client");
00252 
00253   GPSDClient client;
00254 
00255   if (!client.start())
00256     return -1;
00257 
00258 
00259   while(ros::ok()) {
00260     ros::spinOnce();
00261     client.step();
00262   }
00263 
00264   client.stop();
00265 }


gpsd_client
Author(s): Ken Tossell , Rob Thomson
autogenerated on Sat Jun 8 2019 18:37:06