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 (!p->online)
89  return;
90 
91  process_data_gps(p);
92  process_data_navsat(p);
93  }
94 
95 
96 #if GPSD_API_MAJOR_VERSION >= 4
97 #define SATS_VISIBLE p->satellites_visible
98 #elif GPSD_API_MAJOR_VERSION == 3
99 #define SATS_VISIBLE p->satellites
100 #else
101 #error "gpsd_client only supports gpsd API versions 3+"
102 #endif
103 
104  void process_data_gps(struct gps_data_t* p) {
105  ros::Time time = ros::Time::now();
106 
107  GPSFix fix;
108  GPSStatus status;
109 
110  status.header.stamp = time;
111  fix.header.stamp = time;
112  fix.header.frame_id = frame_id;
113 
114  status.satellites_used = p->satellites_used;
115 
116  status.satellite_used_prn.resize(status.satellites_used);
117  for (int i = 0; i < status.satellites_used; ++i) {
118 #if GPSD_API_MAJOR_VERSION > 5
119  status.satellite_used_prn[i] = p->skyview[i].used;
120 #else
121  status.satellite_used_prn[i] = p->used[i];
122 #endif
123  }
124 
125  status.satellites_visible = SATS_VISIBLE;
126 
127  status.satellite_visible_prn.resize(status.satellites_visible);
128  status.satellite_visible_z.resize(status.satellites_visible);
129  status.satellite_visible_azimuth.resize(status.satellites_visible);
130  status.satellite_visible_snr.resize(status.satellites_visible);
131 
132  for (int i = 0; i < SATS_VISIBLE; ++i) {
133 #if GPSD_API_MAJOR_VERSION > 5
134  status.satellite_visible_prn[i] = p->skyview[i].PRN;
135  status.satellite_visible_z[i] = p->skyview[i].elevation;
136  status.satellite_visible_azimuth[i] = p->skyview[i].azimuth;
137  status.satellite_visible_snr[i] = p->skyview[i].ss;
138 #else
139  status.satellite_visible_prn[i] = p->PRN[i];
140  status.satellite_visible_z[i] = p->elevation[i];
141  status.satellite_visible_azimuth[i] = p->azimuth[i];
142  status.satellite_visible_snr[i] = p->ss[i];
143 #endif
144  }
145 
146  if ((p->status & STATUS_FIX) && !(check_fix_by_variance && std::isnan(p->fix.epx))) {
147  status.status = 0; // FIXME: gpsmm puts its constants in the global
148  // namespace, so `GPSStatus::STATUS_FIX' is illegal.
149 
150 // STATUS_DGPS_FIX was removed in API version 6 but re-added afterward
151 #if GPSD_API_MAJOR_VERSION != 6
152  if (p->status & STATUS_DGPS_FIX)
153  status.status |= 18; // same here
154 #endif
155 
156  fix.time = p->fix.time;
157  fix.latitude = p->fix.latitude;
158  fix.longitude = p->fix.longitude;
159  fix.altitude = p->fix.altitude;
160  fix.track = p->fix.track;
161  fix.speed = p->fix.speed;
162  fix.climb = p->fix.climb;
163 
164 #if GPSD_API_MAJOR_VERSION > 3
165  fix.pdop = p->dop.pdop;
166  fix.hdop = p->dop.hdop;
167  fix.vdop = p->dop.vdop;
168  fix.tdop = p->dop.tdop;
169  fix.gdop = p->dop.gdop;
170 #else
171  fix.pdop = p->pdop;
172  fix.hdop = p->hdop;
173  fix.vdop = p->vdop;
174  fix.tdop = p->tdop;
175  fix.gdop = p->gdop;
176 #endif
177 
178  fix.err = p->epe;
179  fix.err_vert = p->fix.epv;
180  fix.err_track = p->fix.epd;
181  fix.err_speed = p->fix.eps;
182  fix.err_climb = p->fix.epc;
183  fix.err_time = p->fix.ept;
184 
185  /* TODO: attitude */
186  } else {
187  status.status = -1; // STATUS_NO_FIX
188  }
189 
190  fix.status = status;
191 
192  gps_fix_pub.publish(fix);
193  }
194 
195  void process_data_navsat(struct gps_data_t* p) {
196  NavSatFixPtr fix(new NavSatFix);
197 
198  /* TODO: Support SBAS and other GBAS. */
199 
200  if (use_gps_time && !std::isnan(p->fix.time))
201  fix->header.stamp = ros::Time(p->fix.time);
202  else
203  fix->header.stamp = ros::Time::now();
204 
205  fix->header.frame_id = frame_id;
206 
207  /* gpsmm pollutes the global namespace with STATUS_,
208  * so we need to use the ROS message's integer values
209  * for status.status
210  */
211  switch (p->status) {
212  case STATUS_NO_FIX:
213  fix->status.status = -1; // NavSatStatus::STATUS_NO_FIX;
214  break;
215  case STATUS_FIX:
216  fix->status.status = 0; // NavSatStatus::STATUS_FIX;
217  break;
218 // STATUS_DGPS_FIX was removed in API version 6 but re-added afterward
219 #if GPSD_API_MAJOR_VERSION != 6
220  case STATUS_DGPS_FIX:
221  fix->status.status = 2; // NavSatStatus::STATUS_GBAS_FIX;
222  break;
223 #endif
224  }
225 
226  fix->status.service = NavSatStatus::SERVICE_GPS;
227 
228  fix->latitude = p->fix.latitude;
229  fix->longitude = p->fix.longitude;
230  fix->altitude = p->fix.altitude;
231 
232  /* gpsd reports status=OK even when there is no current fix,
233  * as long as there has been a fix previously. Throw out these
234  * fake results, which have NaN variance
235  */
236  if (std::isnan(p->fix.epx) && check_fix_by_variance) {
237  return;
238  }
239 
240  fix->position_covariance[0] = p->fix.epx;
241  fix->position_covariance[4] = p->fix.epy;
242  fix->position_covariance[8] = p->fix.epv;
243 
244  fix->position_covariance_type = NavSatFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
245 
246  navsat_fix_pub.publish(fix);
247  }
248 };
249 
250 int main(int argc, char ** argv) {
251  ros::init(argc, argv, "gpsd_client");
252 
253  GPSDClient client;
254 
255  if (!client.start())
256  return -1;
257 
258 
259  while(ros::ok()) {
260  ros::spinOnce();
261  client.step();
262  }
263 
264  client.stop();
265 }
void publish(const boost::shared_ptr< M > &message) const
void process_data_navsat(struct gps_data_t *p)
Definition: client.cpp:195
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:104
int main(int argc, char **argv)
Definition: client.cpp:250
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 Fri Jun 7 2019 21:42:11