00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #include <ros/ros.h>
00037
00038
00039 #include <sensor_msgs/NavSatFix.h>
00040 #include <sensor_msgs/Imu.h>
00041 #include <sensor_msgs/TimeReference.h>
00042 #include <geometry_msgs/TwistWithCovarianceStamped.h>
00043 #include <nav_msgs/Odometry.h>
00044 #include <std_msgs/String.h>
00045
00046
00047 #include <tf/LinearMath/Quaternion.h>
00048 #include <tf/transform_datatypes.h>
00049
00050
00051 #include "dispatch.h"
00052
00053
00054 #include <gps_common/conversions.h>
00055
00056
00057 #include <arpa/inet.h>
00058
00059
00060 #ifndef UINT16_MAX
00061 #define UINT16_MAX (65535)
00062 #endif
00063
00064
00065 #define GPS_LEAP_SECONDS 18 // Offset to account for UTC leap seconds (need to increment when UTC changes)
00066 #define GPS_EPOCH_OFFSET 315964800 // Offset to account for GPS / UTC epoch difference
00067
00068
00069 static inline bool openSocket(const std::string &interface, const std::string &ip_addr, uint16_t port, int *fd_ptr, sockaddr_in *sock_ptr)
00070 {
00071
00072 int fd;
00073 fd = socket(AF_INET, SOCK_DGRAM, IPPROTO_UDP);
00074 if (fd != -1) {
00075 if (interface.length()) {
00076 if (!setsockopt(fd, SOL_SOCKET, SO_BINDTODEVICE, interface.c_str(), interface.length()) == 0) {
00077 close(fd);
00078 return false;
00079 }
00080 }
00081 memset(sock_ptr, 0, sizeof(sockaddr_in));
00082 sock_ptr->sin_family = AF_INET;
00083 sock_ptr->sin_port = htons(port);
00084 if (!inet_aton(ip_addr.c_str(), &sock_ptr->sin_addr)) {
00085 sock_ptr->sin_addr.s_addr = INADDR_ANY;
00086 }
00087 if (bind(fd, (sockaddr*)sock_ptr, sizeof(sockaddr)) == 0) {
00088 *fd_ptr = fd;
00089 return true;
00090 }
00091 }
00092 return false;
00093 }
00094
00095 static inline int readSocket(int fd, unsigned int timeout, void *data, size_t size, sockaddr *source_ptr = NULL)
00096 {
00097 if (fd >= 0) {
00098 fd_set fds;
00099 FD_ZERO(&fds);
00100 FD_SET(fd, &fds);
00101
00102
00103 struct timeval tv;
00104 tv.tv_sec = timeout / 1000;
00105 tv.tv_usec = (timeout * 1000) % 1000000;
00106
00107 if (select(fd + 1, &fds, NULL, NULL, &tv) > 0) {
00108 socklen_t socklen = source_ptr ? sizeof(*source_ptr) : 0;
00109 socklen_t *socklen_ptr = source_ptr ? &socklen : NULL;
00110 return recvfrom(fd, data, size, 0, source_ptr, socklen_ptr);
00111 }
00112
00113
00114 return 0;
00115 }
00116 return -1;
00117 }
00118
00119 static inline double SQUARE(double x) { return x * x; }
00120
00121 #ifndef OXFORD_DISPLAY_INFO
00122 #define OXFORD_DISPLAY_INFO 0
00123 #endif
00124
00125 static const std::map<uint8_t, std::string> POS_MODE_MAP = {
00126 {MODE_NONE, "NONE"},
00127 {MODE_NO_DATA, "NONE"},
00128 {MODE_BLANKED, "NONE"},
00129 {MODE_SEARCH, "SEARCHING"},
00130 {MODE_NOT_RECOGNISED, "NONE"},
00131 {MODE_UNKNOWN, "NONE"},
00132 {MODE_DOPPLER, "DOPPLER"},
00133 {MODE_DOPPLER_PP, "DOPPLER"},
00134 {MODE_DOPPLER_GX, "DOPPLER"},
00135 {MODE_DOPPLER_IX, "DOPPLER"},
00136 {MODE_SPS, "POINT_POSITION"},
00137 {MODE_SPS_PP, "POINT_POSITION"},
00138 {MODE_SPS_GX, "POINT_POSITION"},
00139 {MODE_SPS_IX, "POINT_POSITION"},
00140 {MODE_DIFFERENTIAL, "DIFF_PSEUDORANGE"},
00141 {MODE_DIFFERENTIAL_PP, "DIFF_PSEUDORANGE"},
00142 {MODE_DIFFERENTIAL_GX, "DIFF_PSEUDORANGE"},
00143 {MODE_DIFFERENTIAL_IX, "DIFF_PSEUDORANGE"},
00144 {MODE_RTK_FLOAT, "RTK_FLOAT"},
00145 {MODE_RTK_FLOAT_PP, "RTK_FLOAT"},
00146 {MODE_RTK_FLOAT_GX, "RTK_FLOAT"},
00147 {MODE_RTK_FLOAT_IX, "RTK_FLOAT"},
00148 {MODE_RTK_INTEGER, "RTK_INTEGER"},
00149 {MODE_RTK_INTEGER_PP, "RTK_INTEGER"},
00150 {MODE_RTK_INTEGER_GX, "RTK_INTEGER"},
00151 {MODE_RTK_INTEGER_IX, "RTK_INTEGER"},
00152 {MODE_WAAS, "WAAS"},
00153 {MODE_OMNISTAR_VBS, "OMNISTAR_VBS"},
00154 {MODE_OMNISTAR_HP, "OMNISTAR_HP"},
00155 {MODE_OMNISTAR_XP, "OMNISTAR_XP"},
00156 {MODE_CDGPS, "CANADA_DGPS"},
00157 {MODE_PPP_CONVERGING, "PPP_CONVERGING"},
00158 {MODE_PPP, "PPP"}
00159 };
00160
00161 static const std::map<uint8_t, std::string> NAV_STATUS_MAP = {
00162 {0, "INVALID"},
00163 {1, "IMU_ONLY"},
00164 {2, "INITIALIZING"},
00165 {3, "LOCKING"},
00166 {4, "READY"},
00167 };
00168
00169 static inline void mapLookup(const std::map<uint8_t, std::string>& map, uint8_t key, std::string& val) {
00170 std::map<uint8_t, std::string>::const_iterator it = map.find(key);
00171 if (it != map.end()) {
00172 val = map.at(key);
00173 } else {
00174 val = "UNKNOWN";
00175 }
00176 }
00177
00178 static inline double getZoneMeridian(const std::string& utm_zone)
00179 {
00180 int zone_number = std::atoi(utm_zone.substr(0,2).c_str());
00181 return (zone_number == 0) ? 0.0 : (zone_number - 1) * 6.0 - 177.0;
00182 }
00183
00184 static inline double toUtcTime(uint32_t gps_minutes, uint16_t gps_ms)
00185 {
00186 return GPS_EPOCH_OFFSET - GPS_LEAP_SECONDS + 60.0 * (double)gps_minutes + 0.001 * (double)gps_ms;
00187 }
00188
00189 static inline void handlePacket(const Packet *packet, ros::Publisher &pub_fix, ros::Publisher &pub_vel,
00190 ros::Publisher &pub_imu, ros::Publisher &pub_odom, ros::Publisher &pub_pos_type,
00191 ros::Publisher &pub_nav_status, ros::Publisher &pub_gps_time_ref, const std::string & frame_id_gps,
00192 const std::string &frame_id_vel, const std::string &frame_id_odom)
00193 {
00194 static uint8_t fix_status = sensor_msgs::NavSatStatus::STATUS_FIX;
00195 static uint8_t position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN;
00196 static double position_covariance[3];
00197 static uint8_t velocity_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN;
00198 static double velocity_covariance[3];
00199 static uint8_t orientation_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN;
00200 static double orientation_covariance[3];
00201 static uint8_t pos_mode = 0;
00202 static int none_type_count = 0;
00203
00204 ros::Time stamp = ros::Time::now();
00205
00206 switch (packet->channel) {
00207 case 0:
00208 if (packet->chan.chan0.position_mode != MODE_NONE) {
00209 pos_mode = packet->chan.chan0.position_mode;
00210 none_type_count = 0;
00211 } else {
00212 if (none_type_count > 2) {
00213 none_type_count = 0;
00214 pos_mode = MODE_NONE;
00215 } else {
00216 none_type_count++;
00217 }
00218 }
00219
00220 if (packet->chan.chan0.gps_minutes > 1000) {
00221 sensor_msgs::TimeReference gps_time_ref_msg;
00222 gps_time_ref_msg.source = "gps";
00223 gps_time_ref_msg.header.stamp = stamp;
00224 gps_time_ref_msg.time_ref = ros::Time(toUtcTime(packet->chan.chan0.gps_minutes, packet->time));
00225 pub_gps_time_ref.publish(gps_time_ref_msg);
00226 }
00227
00228 switch (pos_mode) {
00229 case MODE_DIFFERENTIAL:
00230 case MODE_DIFFERENTIAL_PP:
00231 case MODE_DIFFERENTIAL_GX:
00232 case MODE_DIFFERENTIAL_IX:
00233 case MODE_RTK_FLOAT:
00234 case MODE_RTK_FLOAT_PP:
00235 case MODE_RTK_FLOAT_GX:
00236 case MODE_RTK_FLOAT_IX:
00237 case MODE_RTK_INTEGER:
00238 case MODE_RTK_INTEGER_PP:
00239 case MODE_RTK_INTEGER_GX:
00240 case MODE_RTK_INTEGER_IX:
00241 fix_status = sensor_msgs::NavSatStatus::STATUS_GBAS_FIX;
00242 break;
00243 case MODE_OMNISTAR_VBS:
00244 case MODE_OMNISTAR_HP:
00245 case MODE_OMNISTAR_XP:
00246 case MODE_WAAS:
00247 case MODE_CDGPS:
00248 fix_status = sensor_msgs::NavSatStatus::STATUS_SBAS_FIX;
00249 break;
00250 case MODE_SPS:
00251 case MODE_SPS_PP:
00252 case MODE_SPS_GX:
00253 case MODE_SPS_IX:
00254 fix_status = sensor_msgs::NavSatStatus::STATUS_FIX;
00255 break;
00256 case MODE_NONE:
00257 case MODE_SEARCH:
00258 case MODE_DOPPLER:
00259 case MODE_NO_DATA:
00260 case MODE_BLANKED:
00261 case MODE_NOT_RECOGNISED:
00262 case MODE_UNKNOWN:
00263 default:
00264 fix_status = sensor_msgs::NavSatStatus::STATUS_NO_FIX;
00265 break;
00266 }
00267 #if OXFORD_DISPLAY_INFO
00268 ROS_INFO("Num Sats: %u, Position mode: %u, Velocity mode: %u, Orientation mode: %u",
00269 packet->chan.chan0.num_sats,
00270 packet->chan.chan0.position_mode,
00271 packet->chan.chan0.velocity_mode,
00272 packet->chan.chan0.orientation_mode);
00273 #endif
00274 break;
00275 case 3:
00276 if (packet->chan.chan3.age < 150) {
00277 position_covariance[0] = SQUARE((double)packet->chan.chan3.acc_position_east * 1e-3);
00278 position_covariance[1] = SQUARE((double)packet->chan.chan3.acc_position_north * 1e-3);
00279 position_covariance[2] = SQUARE((double)packet->chan.chan3.acc_position_down * 1e-3);
00280 position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
00281 #if OXFORD_DISPLAY_INFO
00282 ROS_INFO("Position accuracy: North: %umm, East: %umm, Down: %umm",
00283 packet->chan.chan3.acc_position_north,
00284 packet->chan.chan3.acc_position_east,
00285 packet->chan.chan3.acc_position_down);
00286 #endif
00287 } else {
00288 position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN;
00289 }
00290 break;
00291 case 4:
00292 if (packet->chan.chan4.age < 150) {
00293 velocity_covariance[0] = SQUARE((double)packet->chan.chan4.acc_velocity_east * 1e-3);
00294 velocity_covariance[1] = SQUARE((double)packet->chan.chan4.acc_velocity_north * 1e-3);
00295 velocity_covariance[2] = SQUARE((double)packet->chan.chan4.acc_velocity_down * 1e-3);
00296 velocity_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
00297 #if OXFORD_DISPLAY_INFO
00298 ROS_INFO("Velocity accuracy: North: %umm/s, East: %umm/s, Down: %umm/s",
00299 packet->chan.chan4.acc_velocity_north,
00300 packet->chan.chan4.acc_velocity_east,
00301 packet->chan.chan4.acc_velocity_down);
00302 #endif
00303 } else {
00304 velocity_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN;
00305 }
00306 break;
00307
00308 case 5:
00309 if (packet->chan.chan5.age < 150) {
00310 orientation_covariance[0] = SQUARE((double)packet->chan.chan5.acc_roll * 1e-5);
00311 orientation_covariance[1] = SQUARE((double)packet->chan.chan5.acc_pitch * 1e-5);
00312 orientation_covariance[2] = SQUARE((double)packet->chan.chan5.acc_heading * 1e-5);
00313 orientation_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
00314 #if OXFORD_DISPLAY_INFO
00315 ROS_INFO("Velocity accuracy: Heading: %frad, Pitch: %frad, Roll: %frad",
00316 (double)packet->chan.chan5.acc_heading * 1e-5,
00317 (double)packet->chan.chan5.acc_pitch * 1e-5,
00318 (double)packet->chan.chan5.acc_roll * 1e-5);
00319 #endif
00320 } else {
00321 orientation_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN;
00322 }
00323 break;
00324 case 23:
00325 #if OXFORD_DISPLAY_INFO
00326 ROS_INFO("Delay: %ums", packet->chan.chan23.delay_ms);
00327 #endif
00328 break;
00329 case 27:
00330 #if OXFORD_DISPLAY_INFO
00331 ROS_INFO("Heading quality: %u", packet->chan.chan27.heading_quality);
00332 #endif
00333 break;
00334 case 37:
00335 #if OXFORD_DISPLAY_INFO
00336 if (packet->chan.chan37.valid) {
00337 ROS_INFO("Heading Misalignment: Angle: %frad, Accuracy: %frad",
00338 (double)packet->chan.chan37.heading_misalignment_angle * 1e-4,
00339 (double)packet->chan.chan37.heading_misalignment_accuracy * 1e-4);
00340 }
00341 #endif
00342 break;
00343 case 48:
00344 #if OXFORD_DISPLAY_INFO
00345 ROS_INFO("HDOP: %0.1f, PDOP: %0.1f",
00346 (double)packet->chan.chan48.HDOP * 1e-1,
00347 (double)packet->chan.chan48.PDOP * 1e-1);
00348 #endif
00349 break;
00350 }
00351 std_msgs::String str_msg;
00352 mapLookup(POS_MODE_MAP, pos_mode, str_msg.data);
00353 pub_pos_type.publish(str_msg);
00354 mapLookup(NAV_STATUS_MAP, packet->nav_status, str_msg.data);
00355 pub_nav_status.publish(str_msg);
00356
00357 if (packet->nav_status == 4) {
00358
00359 double utm_x;
00360 double utm_y;
00361 std::string utm_zone;
00362 gps_common::LLtoUTM(180.0 / M_PI * packet->latitude, 180.0 / M_PI * packet->longitude, utm_y, utm_x, utm_zone);
00363
00364
00365 double central_meridian = M_PI / 180.0 * getZoneMeridian(utm_zone);
00366 double convergence_angle = atan(tan(packet->longitude - central_meridian) * sin(packet->latitude));
00367 double enu_heading = M_PI_2 - (double)packet->heading * 1e-6;
00368 double grid_heading = enu_heading + convergence_angle;
00369
00370
00371 double east_vel = (double)packet->vel_east * 1e-4;
00372 double north_vel = (double)packet->vel_north * 1e-4;
00373 double local_x_vel = east_vel * cos(enu_heading) + north_vel * sin(enu_heading);
00374 double local_y_vel = -east_vel * sin(enu_heading) + north_vel * cos(enu_heading);
00375
00376 sensor_msgs::NavSatFix msg_fix;
00377 msg_fix.header.stamp = stamp;
00378 msg_fix.header.frame_id = frame_id_gps;
00379 msg_fix.latitude = packet->latitude * (180 / M_PI);
00380 msg_fix.longitude = packet->longitude * (180 / M_PI);
00381 msg_fix.altitude = packet->altitude;
00382 msg_fix.status.status = fix_status;
00383 msg_fix.status.service = sensor_msgs::NavSatStatus::SERVICE_GPS;
00384 msg_fix.position_covariance_type = position_covariance_type;
00385 if (position_covariance_type > sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN) {
00386 msg_fix.position_covariance[0] = position_covariance[0];
00387 msg_fix.position_covariance[4] = position_covariance[1];
00388 msg_fix.position_covariance[8] = position_covariance[2];
00389 }
00390 pub_fix.publish(msg_fix);
00391
00392 geometry_msgs::TwistWithCovarianceStamped msg_vel;
00393 msg_vel.header.stamp = stamp;
00394 msg_vel.header.frame_id = frame_id_vel;
00395 msg_vel.twist.twist.linear.x = east_vel;
00396 msg_vel.twist.twist.linear.y = north_vel;
00397 msg_vel.twist.twist.linear.z = (double)packet->vel_down * -1e-4;
00398 if (velocity_covariance_type > sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN) {
00399 msg_vel.twist.covariance[0] = velocity_covariance[0];
00400 msg_vel.twist.covariance[7] = velocity_covariance[1];
00401 msg_vel.twist.covariance[14] = velocity_covariance[2];
00402 }
00403 pub_vel.publish(msg_vel);
00404
00405 tf::Quaternion q;
00406 q.setRPY((double)packet->roll * 1e-6, (double)packet->pitch * 1e-6, enu_heading);
00407 sensor_msgs::Imu msg_imu;
00408 msg_imu.header.stamp = stamp;
00409 msg_imu.header.frame_id = frame_id_gps;
00410 msg_imu.linear_acceleration.x = (double)packet->accel_x * 1e-4;
00411 msg_imu.linear_acceleration.y = (double)packet->accel_y * 1e-4;
00412 msg_imu.linear_acceleration.z = (double)packet->accel_z * -1e-4;
00413 msg_imu.angular_velocity.x = (double)packet->gyro_x * 1e-5;
00414 msg_imu.angular_velocity.y = (double)packet->gyro_y * 1e-5;
00415 msg_imu.angular_velocity.z = (double)packet->gyro_z * -1e-5;
00416 msg_imu.orientation.w = q.w();
00417 msg_imu.orientation.x = q.x();
00418 msg_imu.orientation.y = q.y();
00419 msg_imu.orientation.z = q.z();
00420 if (orientation_covariance_type > sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN) {
00421 msg_imu.orientation_covariance[0] = orientation_covariance[0];
00422 msg_imu.orientation_covariance[4] = orientation_covariance[1];
00423 msg_imu.orientation_covariance[8] = orientation_covariance[2];
00424 }
00425 pub_imu.publish(msg_imu);
00426
00427 nav_msgs::Odometry msg_odom;
00428 msg_odom.header.stamp = stamp;
00429 msg_odom.header.frame_id = "utm";
00430 msg_odom.child_frame_id = frame_id_odom;
00431 msg_odom.pose.pose.position.x = utm_x;
00432 msg_odom.pose.pose.position.y = utm_y;
00433 msg_odom.pose.pose.orientation = tf::createQuaternionMsgFromYaw(grid_heading);
00434
00435
00436 double std_east = (double)packet->chan.chan3.acc_position_east * 1e-3;
00437 double std_north = (double)packet->chan.chan3.acc_position_north * 1e-3;
00438 double std_x = std_east * cos(convergence_angle) - std_north * sin(convergence_angle);
00439 double std_y = std_north * sin(convergence_angle) + std_east * cos(convergence_angle);
00440
00441
00442 double std_east_vel = (double)packet->chan.chan4.acc_velocity_east * 1e-3;
00443 double std_north_vel = (double)packet->chan.chan4.acc_velocity_north * 1e-3;
00444 double std_x_vel = std_east_vel * cos(enu_heading) + std_north_vel * sin(enu_heading);
00445 double std_y_vel = -std_east_vel * cos(enu_heading) + std_north_vel * sin(enu_heading);
00446
00447 msg_odom.pose.covariance[0*6 + 0] = SQUARE(std_x);
00448 msg_odom.pose.covariance[1*6 + 1] = SQUARE(std_y);
00449 msg_odom.pose.covariance[5*6 + 5] = orientation_covariance[2];
00450 msg_odom.twist.twist.linear.x = local_x_vel;
00451 msg_odom.twist.twist.linear.y = local_y_vel;
00452 msg_odom.twist.twist.angular.z = msg_imu.angular_velocity.z;
00453 msg_odom.twist.covariance[0*6 + 0] = SQUARE(std_x_vel);
00454 msg_odom.twist.covariance[1*6 + 1] = SQUARE(std_y_vel);
00455 pub_odom.publish(msg_odom);
00456
00457 #if OXFORD_DISPLAY_INFO
00458 } else {
00459 ROS_WARN("Nav Status: %u", packet->nav_status);
00460 #endif
00461 }
00462 }
00463
00464 int main(int argc, char **argv)
00465 {
00466 ros::init(argc, argv, "oxford_gps");
00467 ros::NodeHandle node;
00468 ros::NodeHandle priv_nh("~");
00469
00470 std::string interface = "";
00471 priv_nh.getParam("interface", interface);
00472
00473 std::string ip_addr = "";
00474 priv_nh.getParam("ip_address", ip_addr);
00475
00476 int port = 3000;
00477 priv_nh.getParam("port", port);
00478
00479 std::string frame_id_gps = "gps";
00480 priv_nh.getParam("frame_id_gps", frame_id_gps);
00481
00482 std::string frame_id_vel = "enu";
00483 priv_nh.getParam("frame_id_vel", frame_id_vel);
00484
00485 std::string frame_id_odom = "base_footprint";
00486 priv_nh.getParam("frame_id_odom", frame_id_odom);
00487
00488 if (port > UINT16_MAX) {
00489 ROS_ERROR("Port %u greater than maximum value of %u", port, UINT16_MAX);
00490 }
00491
00492 if (interface.length() && ip_addr.length()) {
00493 ROS_INFO("Preparing to listen on interface %s port %u and IP %s", interface.c_str(), port, ip_addr.c_str());
00494 } else if (interface.length()) {
00495 ROS_INFO("Preparing to listen on interface %s port %u", interface.c_str(), port);
00496 } else if (ip_addr.length()) {
00497 ROS_INFO("Preparing to listen on %s:%u", ip_addr.c_str(), port);
00498 } else {
00499 ROS_INFO("Preparing to listen on port %u", port);
00500 }
00501
00502 int fd;
00503 sockaddr_in sock;
00504 if (openSocket(interface, ip_addr, port, &fd, &sock)) {
00505
00506 ros::Publisher pub_fix = node.advertise<sensor_msgs::NavSatFix>("gps/fix", 2);
00507 ros::Publisher pub_vel = node.advertise<geometry_msgs::TwistWithCovarianceStamped>("gps/vel", 2);
00508 ros::Publisher pub_imu = node.advertise<sensor_msgs::Imu>("imu/data", 2);
00509 ros::Publisher pub_odom = node.advertise<nav_msgs::Odometry>("gps/odom", 2);
00510 ros::Publisher pub_pos_type = node.advertise<std_msgs::String>("gps/pos_type", 2);
00511 ros::Publisher pub_nav_status = node.advertise<std_msgs::String>("gps/nav_status", 2);
00512 ros::Publisher pub_gps_time_ref = node.advertise<sensor_msgs::TimeReference>("gps/time_ref", 2);
00513
00514
00515 Packet packet;
00516 sockaddr source;
00517 bool first = true;
00518
00519
00520 while (ros::ok()) {
00521 if (readSocket(fd, 10, &packet, sizeof(packet), &source) >= sizeof(packet)) {
00522 if (validatePacket(&packet)) {
00523 if (first) {
00524 first = false;
00525 ROS_INFO("Connected to Oxford GPS at %s:%u", inet_ntoa(((sockaddr_in*)&source)->sin_addr), htons(((sockaddr_in*)&source)->sin_port));
00526 }
00527 handlePacket(&packet, pub_fix, pub_vel, pub_imu, pub_odom, pub_pos_type, pub_nav_status, pub_gps_time_ref, frame_id_gps, frame_id_vel, frame_id_odom);
00528 }
00529 }
00530
00531
00532 ros::spinOnce();
00533 }
00534
00535
00536 close(fd);
00537 } else {
00538 ROS_FATAL("Failed to open socket");
00539 ros::WallDuration(1.0).sleep();
00540 }
00541
00542 return 0;
00543 }