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 using namespace gps_common;
00009 using namespace sensor_msgs;
00010
00011 class GPSDClient {
00012 public:
00013 GPSDClient() : privnode("~") {}
00014
00015 bool start() {
00016 gps_fix_pub = node.advertise<GPSFix>("extended_fix", 1);
00017 navsat_fix_pub = node.advertise<NavSatFix>("fix", 1);
00018
00019 std::string host = "localhost";
00020 int port = 2947;
00021 privnode.getParam("host", host);
00022 privnode.getParam("port", port);
00023
00024 char port_s[12];
00025 snprintf(port_s, 12, "%d", port);
00026
00027 gps_data_t *resp = gps.open(host.c_str(), port_s);
00028 if (resp == NULL) {
00029 ROS_ERROR("Failed to open GPSd");
00030 return false;
00031 }
00032
00033 #if GPSD_API_MAJOR_VERSION == 4
00034 resp = gps.stream(WATCH_ENABLE);
00035 #elif GPSD_API_MAJOR_VERSION == 3
00036 gps.query("w\n");
00037 #else
00038 #error "gpsd_client only supports gpsd API versions 3 and 4"
00039 #endif
00040
00041 ROS_INFO("GPSd opened");
00042 return true;
00043 }
00044
00045 void step() {
00046 gps_data_t *p = gps.poll();
00047 process_data(p);
00048 }
00049
00050 void stop() {
00051
00052 }
00053
00054 private:
00055 ros::NodeHandle node;
00056 ros::NodeHandle privnode;
00057 ros::Publisher gps_fix_pub;
00058 ros::Publisher navsat_fix_pub;
00059 gpsmm gps;
00060
00061 void process_data(struct gps_data_t* p) {
00062 if (p == NULL)
00063 return;
00064
00065 if (!p->online)
00066 return;
00067
00068 process_data_gps(p);
00069 process_data_navsat(p);
00070 }
00071
00072
00073 #if GPSD_API_MAJOR_VERSION == 4
00074 #define SATS_VISIBLE p->satellites_visible
00075 #elif GPSD_API_MAJOR_VERSION == 3
00076 #define SATS_VISIBLE p->satellites
00077 #endif
00078
00079 void process_data_gps(struct gps_data_t* p) {
00080 ros::Time time = ros::Time::now();
00081
00082 GPSFix fix;
00083 GPSStatus status;
00084
00085 status.header.stamp = time;
00086 fix.header.stamp = time;
00087
00088 status.satellites_used = p->satellites_used;
00089
00090 status.satellite_used_prn.resize(status.satellites_used);
00091 for (int i = 0; i < status.satellites_used; ++i) {
00092 status.satellite_used_prn[i] = p->used[i];
00093 }
00094
00095 status.satellites_visible = SATS_VISIBLE;
00096
00097 status.satellite_visible_prn.resize(status.satellites_visible);
00098 status.satellite_visible_z.resize(status.satellites_visible);
00099 status.satellite_visible_azimuth.resize(status.satellites_visible);
00100 status.satellite_visible_snr.resize(status.satellites_visible);
00101
00102 for (int i = 0; i < SATS_VISIBLE; ++i) {
00103 status.satellite_visible_prn[i] = p->PRN[i];
00104 status.satellite_visible_z[i] = p->elevation[i];
00105 status.satellite_visible_azimuth[i] = p->azimuth[i];
00106 status.satellite_visible_snr[i] = p->ss[i];
00107 }
00108
00109 if (p->status & STATUS_FIX) {
00110 status.status = 0;
00111
00112
00113 if (p->status & STATUS_DGPS_FIX)
00114 status.status |= 18;
00115
00116 fix.time = p->fix.time;
00117 fix.latitude = p->fix.latitude;
00118 fix.longitude = p->fix.longitude;
00119 fix.altitude = p->fix.altitude;
00120 fix.track = p->fix.track;
00121 fix.speed = p->fix.speed;
00122 fix.climb = p->fix.climb;
00123
00124 #if GPSD_API_MAJOR_VERSION > 3
00125 fix.pdop = p->dop.pdop;
00126 fix.hdop = p->dop.hdop;
00127 fix.vdop = p->dop.vdop;
00128 fix.tdop = p->dop.tdop;
00129 fix.gdop = p->dop.gdop;
00130 #else
00131 fix.pdop = p->pdop;
00132 fix.hdop = p->hdop;
00133 fix.vdop = p->vdop;
00134 fix.tdop = p->tdop;
00135 fix.gdop = p->gdop;
00136 #endif
00137
00138 fix.err = p->epe;
00139 fix.err_vert = p->fix.epv;
00140 fix.err_track = p->fix.epd;
00141 fix.err_speed = p->fix.eps;
00142 fix.err_climb = p->fix.epc;
00143 fix.err_time = p->fix.ept;
00144
00145
00146 } else {
00147 status.status = -1;
00148 }
00149
00150 fix.status = status;
00151
00152 gps_fix_pub.publish(fix);
00153 }
00154
00155 void process_data_navsat(struct gps_data_t* p) {
00156 NavSatFixPtr fix(new NavSatFix);
00157
00158
00159 fix->header.stamp = ros::Time(p->fix.time);
00160
00161
00162
00163
00164
00165 switch (p->status) {
00166 case STATUS_NO_FIX:
00167 fix->status.status = -1;
00168 break;
00169 case STATUS_FIX:
00170 fix->status.status = 0;
00171 break;
00172 case STATUS_DGPS_FIX:
00173 fix->status.status = 2;
00174 break;
00175 }
00176
00177 fix->status.service = NavSatStatus::SERVICE_GPS;
00178
00179 fix->latitude = p->fix.latitude;
00180 fix->longitude = p->fix.longitude;
00181 fix->altitude = p->fix.altitude;
00182
00183 fix->position_covariance[0] = p->fix.epx;
00184 fix->position_covariance[4] = p->fix.epy;
00185 fix->position_covariance[8] = p->fix.epv;
00186
00187 fix->position_covariance_type = NavSatFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
00188
00189 navsat_fix_pub.publish(fix);
00190 }
00191 };
00192
00193 int main(int argc, char ** argv) {
00194 ros::init(argc, argv, "gpsd_client");
00195
00196 GPSDClient client;
00197
00198 if (!client.start())
00199 return -1;
00200
00201
00202 while(ros::ok()) {
00203 ros::spinOnce();
00204 client.step();
00205 }
00206
00207 client.stop();
00208 }