client.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
2 #include <gps_common/GPSFix.h>
3 #include <gps_common/GPSStatus.h>
4 #include <sensor_msgs/NavSatFix.h>
5 #include <sensor_msgs/NavSatStatus.h>
6 #include <libgpsmm.h>
7 
8 #include <cmath>
9 
10 using namespace gps_common;
11 using namespace sensor_msgs;
12 
13 class GPSDClient {
14  public:
15  GPSDClient() : privnode("~"), gps(NULL), use_gps_time(true), check_fix_by_variance(true), frame_id("gps") {}
16 
17  bool start() {
18  gps_fix_pub = node.advertise<GPSFix>("extended_fix", 1);
19  navsat_fix_pub = node.advertise<NavSatFix>("fix", 1);
20 
21  privnode.getParam("use_gps_time", use_gps_time);
22  privnode.getParam("check_fix_by_variance", check_fix_by_variance);
23  privnode.param("frame_id", frame_id, frame_id);
24 
25  std::string host = "localhost";
26  int port = 2947;
27  privnode.getParam("host", host);
28  privnode.getParam("port", port);
29 
30  char port_s[12];
31  snprintf(port_s, 12, "%d", port);
32 
33  gps_data_t *resp = NULL;
34 
35 #if GPSD_API_MAJOR_VERSION >= 5
36  gps = new gpsmm(host.c_str(), port_s);
37  resp = gps->stream(WATCH_ENABLE);
38 #elif GPSD_API_MAJOR_VERSION == 4
39  gps = new gpsmm();
40  gps->open(host.c_str(), port_s);
41  resp = gps->stream(WATCH_ENABLE);
42 #else
43  gps = new gpsmm();
44  resp = gps->open(host.c_str(), port_s);
45  gps->query("w\n");
46 #endif
47 
48  if (resp == NULL) {
49  ROS_ERROR("Failed to open GPSd");
50  return false;
51  }
52 
53  ROS_INFO("GPSd opened");
54  return true;
55  }
56 
57  void step() {
58 #if GPSD_API_MAJOR_VERSION >= 5
59  if (!gps->waiting(1e6))
60  return;
61 
62  gps_data_t *p = gps->read();
63 #else
64  gps_data_t *p = gps->poll();
65 #endif
66  process_data(p);
67  }
68 
69  void stop() {
70  // gpsmm doesn't have a close method? OK ...
71  }
72 
73  private:
78  gpsmm *gps;
79 
82  std::string frame_id;
83 
84  void process_data(struct gps_data_t* p) {
85  if (p == NULL)
86  return;
87 
88 #if GPSD_API_MAJOR_VERSION >= 9
89  if (!p->online.tv_sec && !p->online.tv_nsec) {
90 #else
91  if (!p->online) {
92 #endif
93  return;
94  }
95 
96  process_data_gps(p);
97  process_data_navsat(p);
98  }
99 
100 
101 #if GPSD_API_MAJOR_VERSION >= 4
102 #define SATS_VISIBLE p->satellites_visible
103 #elif GPSD_API_MAJOR_VERSION == 3
104 #define SATS_VISIBLE p->satellites
105 #else
106 #error "gpsd_client only supports gpsd API versions 3+"
107 #endif
108 
109  void process_data_gps(struct gps_data_t* p) {
110  ros::Time time = ros::Time::now();
111 
112  GPSFix fix;
113  GPSStatus status;
114 
115  status.header.stamp = time;
116  fix.header.stamp = time;
117  fix.header.frame_id = frame_id;
118 
119  status.satellites_used = p->satellites_used;
120 
121  status.satellite_used_prn.resize(status.satellites_used);
122  for (int i = 0; i < status.satellites_used; ++i) {
123 #if GPSD_API_MAJOR_VERSION > 5
124  status.satellite_used_prn[i] = p->skyview[i].used;
125 #else
126  status.satellite_used_prn[i] = p->used[i];
127 #endif
128  }
129 
130  status.satellites_visible = SATS_VISIBLE;
131 
132  status.satellite_visible_prn.resize(status.satellites_visible);
133  status.satellite_visible_z.resize(status.satellites_visible);
134  status.satellite_visible_azimuth.resize(status.satellites_visible);
135  status.satellite_visible_snr.resize(status.satellites_visible);
136 
137  for (int i = 0; i < SATS_VISIBLE; ++i) {
138 #if GPSD_API_MAJOR_VERSION > 5
139  status.satellite_visible_prn[i] = p->skyview[i].PRN;
140  status.satellite_visible_z[i] = p->skyview[i].elevation;
141  status.satellite_visible_azimuth[i] = p->skyview[i].azimuth;
142  status.satellite_visible_snr[i] = p->skyview[i].ss;
143 #else
144  status.satellite_visible_prn[i] = p->PRN[i];
145  status.satellite_visible_z[i] = p->elevation[i];
146  status.satellite_visible_azimuth[i] = p->azimuth[i];
147  status.satellite_visible_snr[i] = p->ss[i];
148 #endif
149  }
150 
151  if ((p->status & STATUS_FIX) && !(check_fix_by_variance && std::isnan(p->fix.epx))) {
152  status.status = 0; // FIXME: gpsmm puts its constants in the global
153  // namespace, so `GPSStatus::STATUS_FIX' is illegal.
154 
155 // STATUS_DGPS_FIX was removed in API version 6 but re-added afterward
156 #if GPSD_API_MAJOR_VERSION != 6
157  if (p->status & STATUS_DGPS_FIX)
158  status.status |= 18; // same here
159 #endif
160 
161 #if GPSD_API_MAJOR_VERSION >= 9
162  fix.time = (double)(p->fix.time.tv_sec) + (double)(p->fix.time.tv_nsec) / 1000000.;
163 #else
164  fix.time = p->fix.time;
165 #endif
166  fix.latitude = p->fix.latitude;
167  fix.longitude = p->fix.longitude;
168  fix.altitude = p->fix.altitude;
169  fix.track = p->fix.track;
170  fix.speed = p->fix.speed;
171  fix.climb = p->fix.climb;
172 
173 #if GPSD_API_MAJOR_VERSION > 3
174  fix.pdop = p->dop.pdop;
175  fix.hdop = p->dop.hdop;
176  fix.vdop = p->dop.vdop;
177  fix.tdop = p->dop.tdop;
178  fix.gdop = p->dop.gdop;
179 #else
180  fix.pdop = p->pdop;
181  fix.hdop = p->hdop;
182  fix.vdop = p->vdop;
183  fix.tdop = p->tdop;
184  fix.gdop = p->gdop;
185 #endif
186 
187 #if GPSD_API_MAJOR_VERSION < 8
188  fix.err = p->epe;
189 #else
190  fix.err = p->fix.eph;
191 #endif
192  fix.err_vert = p->fix.epv;
193  fix.err_track = p->fix.epd;
194  fix.err_speed = p->fix.eps;
195  fix.err_climb = p->fix.epc;
196  fix.err_time = p->fix.ept;
197 
198  /* TODO: attitude */
199  } else {
200  status.status = -1; // STATUS_NO_FIX
201  }
202 
203  fix.status = status;
204 
205  gps_fix_pub.publish(fix);
206  }
207 
208  void process_data_navsat(struct gps_data_t* p) {
209  NavSatFixPtr fix(new NavSatFix);
210 
211  /* TODO: Support SBAS and other GBAS. */
212 
213 #if GPSD_API_MAJOR_VERSION >= 9
214  if (use_gps_time && (p->online.tv_sec || p->online.tv_nsec)) {
215  fix->header.stamp = ros::Time(p->fix.time.tv_sec, p->fix.time.tv_nsec);
216 #else
217  if (use_gps_time && !std::isnan(p->fix.time)) {
218  fix->header.stamp = ros::Time(p->fix.time);
219 #endif
220  }
221  else {
222  fix->header.stamp = ros::Time::now();
223  }
224 
225  fix->header.frame_id = frame_id;
226 
227  /* gpsmm pollutes the global namespace with STATUS_,
228  * so we need to use the ROS message's integer values
229  * for status.status
230  */
231  switch (p->status) {
232  case STATUS_NO_FIX:
233  fix->status.status = -1; // NavSatStatus::STATUS_NO_FIX;
234  break;
235  case STATUS_FIX:
236  fix->status.status = 0; // NavSatStatus::STATUS_FIX;
237  break;
238 // STATUS_DGPS_FIX was removed in API version 6 but re-added afterward
239 #if GPSD_API_MAJOR_VERSION != 6
240  case STATUS_DGPS_FIX:
241  fix->status.status = 2; // NavSatStatus::STATUS_GBAS_FIX;
242  break;
243 #endif
244  }
245 
246  fix->status.service = NavSatStatus::SERVICE_GPS;
247 
248  fix->latitude = p->fix.latitude;
249  fix->longitude = p->fix.longitude;
250  fix->altitude = p->fix.altitude;
251 
252  /* gpsd reports status=OK even when there is no current fix,
253  * as long as there has been a fix previously. Throw out these
254  * fake results, which have NaN variance
255  */
256  if (std::isnan(p->fix.epx) && check_fix_by_variance) {
257  return;
258  }
259 
260  fix->position_covariance[0] = p->fix.epx;
261  fix->position_covariance[4] = p->fix.epy;
262  fix->position_covariance[8] = p->fix.epv;
263 
264  fix->position_covariance_type = NavSatFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
265 
266  navsat_fix_pub.publish(fix);
267  }
268 };
269 
270 int main(int argc, char ** argv) {
271  ros::init(argc, argv, "gpsd_client");
272 
273  GPSDClient client;
274 
275  if (!client.start())
276  return -1;
277 
278 
279  while(ros::ok()) {
280  ros::spinOnce();
281  client.step();
282  }
283 
284  client.stop();
285 }
void publish(const boost::shared_ptr< M > &message) const
void process_data_navsat(struct gps_data_t *p)
Definition: client.cpp:208
ros::Publisher gps_fix_pub
Definition: client.cpp:76
void step()
Definition: client.cpp:57
void stop()
Definition: client.cpp:69
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::string frame_id
Definition: client.cpp:82
bool check_fix_by_variance
Definition: client.cpp:81
void process_data_gps(struct gps_data_t *p)
Definition: client.cpp:109
int main(int argc, char **argv)
Definition: client.cpp:270
bool use_gps_time
Definition: client.cpp:80
bool start()
Definition: client.cpp:17
#define ROS_INFO(...)
ROSCPP_DECL bool ok()
GPSDClient()
Definition: client.cpp:15
std::string frame_id
gpsmm * gps
Definition: client.cpp:78
ros::NodeHandle privnode
Definition: client.cpp:75
ros::NodeHandle node
Definition: client.cpp:74
static Time now()
ROSCPP_DECL void spinOnce()
#define ROS_ERROR(...)
ros::Publisher navsat_fix_pub
Definition: client.cpp:77
void process_data(struct gps_data_t *p)
Definition: client.cpp:84


gpsd_client
Author(s): Ken Tossell , Rob Thomson
autogenerated on Thu May 28 2020 03:13:34