novatel_gps.cpp
Go to the documentation of this file.
00001 // *****************************************************************************
00002 //
00003 // Copyright (c) 2017, Southwest Research Institute® (SwRI®)
00004 // All rights reserved.
00005 //
00006 // Redistribution and use in source and binary forms, with or without
00007 // modification, are permitted provided that the following conditions are met:
00008 //     * Redistributions of source code must retain the above copyright
00009 //       notice, this list of conditions and the following disclaimer.
00010 //     * Redistributions in binary form must reproduce the above copyright
00011 //       notice, this list of conditions and the following disclaimer in the
00012 //       documentation and/or other materials provided with the distribution.
00013 //     * Neither the name of Southwest Research Institute® (SwRI®) nor the
00014 //       names of its contributors may be used to endorse or promote products
00015 //       derived from this software without specific prior written permission.
00016 //
00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020 // ARE DISCLAIMED. IN NO EVENT SHALL SOUTHWEST RESEARCH INSTITUTE BE LIABLE FOR ANY
00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00027 //
00028 // *****************************************************************************
00029 
00030 #include <sstream>
00031 #include <net/ethernet.h>
00032 #include <netinet/udp.h>
00033 #include <netinet/tcp.h>
00034 #include <netinet/ip.h>
00035 #include <novatel_gps_driver/novatel_gps.h>
00036 
00037 #include <boost/algorithm/string/join.hpp>
00038 #include <boost/make_shared.hpp>
00039 
00040 #include <ros/ros.h>
00041 #include <tf/tf.h>
00042 
00043 namespace novatel_gps_driver
00044 {
00045   NovatelGps::NovatelGps() :
00046       gpgga_gprmc_sync_tol_(0.01),
00047       gpgga_position_sync_tol_(0.01),
00048       wait_for_position_(false),
00049       connection_(SERIAL),
00050       is_connected_(false),
00051       utc_offset_(0),
00052       serial_baud_(115200),
00053       tcp_socket_(io_service_),
00054       pcap_(NULL),
00055       clocksteering_msgs_(MAX_BUFFER_SIZE),
00056       corrimudata_msgs_(MAX_BUFFER_SIZE),
00057       gpgga_msgs_(MAX_BUFFER_SIZE),
00058       gpgga_sync_buffer_(SYNC_BUFFER_SIZE),
00059       gpgsa_msgs_(MAX_BUFFER_SIZE),
00060       gpgsv_msgs_(MAX_BUFFER_SIZE),
00061       gprmc_msgs_(MAX_BUFFER_SIZE),
00062       gprmc_sync_buffer_(SYNC_BUFFER_SIZE),
00063       imu_msgs_(MAX_BUFFER_SIZE),
00064       inscov_msgs_(MAX_BUFFER_SIZE),
00065       inspva_msgs_(MAX_BUFFER_SIZE),
00066       insstdev_msgs_(MAX_BUFFER_SIZE),
00067       heading2_msgs_(MAX_BUFFER_SIZE),
00068       dual_antenna_heading_msgs_(MAX_BUFFER_SIZE),
00069       novatel_positions_(MAX_BUFFER_SIZE),
00070       novatel_xyz_positions_(MAX_BUFFER_SIZE),
00071       novatel_utm_positions_(MAX_BUFFER_SIZE),
00072       novatel_velocities_(MAX_BUFFER_SIZE),
00073       position_sync_buffer_(SYNC_BUFFER_SIZE),
00074       range_msgs_(MAX_BUFFER_SIZE),
00075       time_msgs_(MAX_BUFFER_SIZE),
00076       trackstat_msgs_(MAX_BUFFER_SIZE),
00077       imu_rate_(-1.0),
00078       imu_rate_forced_(false),
00079       apply_vehicle_body_rotation_(false)
00080   {
00081   }
00082 
00083   NovatelGps::~NovatelGps()
00084   {
00085     Disconnect();
00086   }
00087 
00088   bool NovatelGps::Connect(
00089       const std::string& device,
00090       ConnectionType connection)
00091   {
00092     NovatelMessageOpts opts;
00093     opts["gpgga"] = 0.05;
00094     opts["gprmc"] = 0.05;
00095     opts["bestposa"] = 0.05;
00096     opts["timea"] = 1.0;
00097     opts["rangea"] = 1;
00098     return Connect(device, connection, opts);
00099   }
00100 
00101   bool NovatelGps::Connect(
00102       const std::string& device,
00103       ConnectionType connection,
00104       NovatelMessageOpts const& opts)
00105   {
00106     Disconnect();
00107 
00108     connection_ = connection;
00109 
00110     if (connection_ == SERIAL)
00111     {
00112       return CreateSerialConnection(device, opts);
00113     }
00114     else if (connection_ == TCP || connection_ == UDP)
00115     {
00116       return CreateIpConnection(device, opts);
00117     }
00118     else if (connection_ == PCAP)
00119     {
00120       return CreatePcapConnection(device, opts);
00121     }
00122 
00123     error_msg_ = "Invalid connection type.";
00124 
00125     return false;
00126 
00127   }
00128 
00129   NovatelGps::ConnectionType NovatelGps::ParseConnection(const std::string& connection)
00130   {
00131     if (connection == "serial")
00132     {
00133       return SERIAL;
00134     }
00135     else if (connection == "udp")
00136     {
00137       return UDP;
00138     }
00139     else if (connection == "tcp")
00140     {
00141       return TCP;
00142     }
00143     else if (connection == "pcap")
00144     {
00145       return PCAP;
00146     }
00147 
00148     return INVALID;
00149   }
00150 
00151   void NovatelGps::Disconnect()
00152   {
00153     if (connection_ == SERIAL)
00154     {
00155       serial_.Close();
00156     }
00157     else if (connection_ == TCP)
00158     {
00159       tcp_socket_.close();
00160     }
00161     else if (connection_ == UDP)
00162     {
00163       if (udp_socket_)
00164       {
00165         udp_socket_->close();
00166         udp_socket_.reset();
00167       }
00168       if (udp_endpoint_)
00169       {
00170         udp_endpoint_.reset();
00171       }
00172     }
00173     else if (connection_ == PCAP)
00174     {
00175       if (pcap_ != NULL)
00176       {
00177         pcap_close(pcap_);
00178         pcap_ = NULL;
00179       }
00180     }
00181     is_connected_ = false;
00182   }
00183 
00184   void NovatelGps::ApplyVehicleBodyRotation(const bool& apply_rotation)
00185   {
00186     apply_vehicle_body_rotation_ = apply_rotation;
00187   }
00188 
00189   NovatelGps::ReadResult NovatelGps::ProcessData()
00190   {
00191     NovatelGps::ReadResult read_result = ReadData();
00192 
00193     if (read_result != READ_SUCCESS)
00194     {
00195       return read_result;
00196     }
00197 
00198     ros::Time stamp = ros::Time::now();
00199     std::vector<NmeaSentence> nmea_sentences;
00200     std::vector<NovatelSentence> novatel_sentences;
00201     std::vector<BinaryMessage> binary_messages;
00202 
00203     if (!data_buffer_.empty())
00204     {
00205       nmea_buffer_.insert(nmea_buffer_.end(),
00206                           data_buffer_.begin(),
00207                           data_buffer_.end());
00208 
00209       data_buffer_.clear();
00210 
00211       std::string remaining_buffer;
00212 
00213       if (!extractor_.ExtractCompleteMessages(
00214           nmea_buffer_,
00215           nmea_sentences,
00216           novatel_sentences,
00217           binary_messages,
00218           remaining_buffer))
00219       {
00220         read_result = READ_PARSE_FAILED;
00221         error_msg_ = "Parse failure extracting sentences.";
00222       }
00223 
00224       nmea_buffer_ = remaining_buffer;
00225 
00226       ROS_DEBUG("Parsed: %lu NMEA / %lu NovAtel / %lu Binary messages",
00227                nmea_sentences.size(), novatel_sentences.size(), binary_messages.size());
00228       if (!nmea_buffer_.empty())
00229       {
00230         ROS_DEBUG("%lu unparsed bytes left over.", nmea_buffer_.size());
00231       }
00232     }
00233 
00234     double most_recent_utc_time = extractor_.GetMostRecentUtcTime(nmea_sentences);
00235 
00236     for(const auto& sentence : nmea_sentences)
00237     {
00238       try
00239       {
00240         NovatelGps::ReadResult result = ParseNmeaSentence(sentence, stamp, most_recent_utc_time);
00241         if (result != READ_SUCCESS)
00242         {
00243           read_result = result;
00244         }
00245       }
00246       catch (const ParseException& p)
00247       {
00248         error_msg_ = p.what();
00249         ROS_WARN("%s", p.what());
00250         ROS_WARN("For sentence: [%s]", boost::algorithm::join(sentence.body, ",").c_str());
00251         read_result = READ_PARSE_FAILED;
00252       }
00253     }
00254 
00255     for(const auto& sentence : novatel_sentences)
00256     {
00257       try
00258       {
00259         NovatelGps::ReadResult result = ParseNovatelSentence(sentence, stamp);
00260         if (result != READ_SUCCESS)
00261         {
00262           read_result = result;
00263         }
00264       }
00265       catch (const ParseException& p)
00266       {
00267         error_msg_ = p.what();
00268         ROS_WARN("%s", p.what());
00269         read_result = READ_PARSE_FAILED;
00270       }
00271     }
00272 
00273     for(const auto& msg : binary_messages)
00274     {
00275       try
00276       {
00277         NovatelGps::ReadResult result = ParseBinaryMessage(msg, stamp);
00278         if (result != READ_SUCCESS)
00279         {
00280           read_result = result;
00281         }
00282       }
00283       catch (const ParseException& p)
00284       {
00285         error_msg_ = p.what();
00286         ROS_WARN("%s", p.what());
00287         read_result = READ_PARSE_FAILED;
00288       }
00289     }
00290 
00291     return read_result;
00292   }
00293 
00294   void NovatelGps::GetNovatelPositions(std::vector<novatel_gps_msgs::NovatelPositionPtr>& positions)
00295   {
00296     positions.clear();
00297     positions.insert(positions.end(), novatel_positions_.begin(), novatel_positions_.end());
00298     novatel_positions_.clear();
00299   }
00300 
00301   void NovatelGps::GetNovatelXYZPositions(std::vector<novatel_gps_msgs::NovatelXYZPtr>& positions)
00302   {
00303     positions.clear();
00304     positions.insert(positions.end(), novatel_xyz_positions_.begin(), novatel_xyz_positions_.end());
00305     novatel_xyz_positions_.clear();
00306   }
00307 
00308   void NovatelGps::GetNovatelUtmPositions(std::vector<novatel_gps_msgs::NovatelUtmPositionPtr>& utm_positions)
00309   {
00310     utm_positions.clear();
00311     utm_positions.insert(utm_positions.end(), novatel_utm_positions_.begin(), novatel_utm_positions_.end());
00312     novatel_utm_positions_.clear();
00313   }
00314 
00315   void NovatelGps::GetNovatelVelocities(std::vector<novatel_gps_msgs::NovatelVelocityPtr>& velocities)
00316   {
00317     velocities.resize(novatel_velocities_.size());
00318     std::copy(novatel_velocities_.begin(), novatel_velocities_.end(), velocities.begin());
00319     novatel_velocities_.clear();
00320   }
00321 
00322   void NovatelGps::GetFixMessages(std::vector<gps_common::GPSFixPtr>& fix_messages)
00323   {
00324     // Clear out the fix_messages list before filling it
00325     fix_messages.clear();
00326 
00327     // both a gpgga and a gprmc message are required to fill the GPSFix message
00328     while (!gpgga_sync_buffer_.empty() && !gprmc_sync_buffer_.empty())
00329     {
00330       double gpgga_time = gpgga_sync_buffer_.front().utc_seconds;
00331       double gprmc_time = gprmc_sync_buffer_.front().utc_seconds;
00332 
00333       // Find the time difference between gpgga and gprmc time
00334       double dt = gpgga_time - gprmc_time;
00335       // Handle times around midnight
00336       if (dt > 43200.0)
00337       {
00338         dt -= 86400.0;
00339       }
00340       if (dt < -43200.0)
00341       {
00342         dt += 86400.0;
00343       }
00344 
00345       // Get the front elements of the gpgga and gprmc buffers synced to within tolerance
00346       if (dt > gpgga_gprmc_sync_tol_)
00347       {
00348         // The gprmc message is more than tol older than the gpgga message,
00349         // discard it and continue
00350         gprmc_sync_buffer_.pop_front();
00351       }
00352       else if (-dt > gpgga_gprmc_sync_tol_)
00353       {
00354         // The gpgga message is more than tol older than the gprmc message,
00355         // discard it and continue
00356         gpgga_sync_buffer_.pop_front();
00357       }
00358       else // The gpgga and gprmc messages are synced
00359       {
00360         bool has_position = false;
00361         bool pop_position = false;
00362 
00363         // Iterate over the position message buffer until we find one
00364         // that is synced with the gpgga message
00365         while (!position_sync_buffer_.empty())
00366         {
00367           // Calculate UTC position time from GPS seconds by subtracting out
00368           // full days and applying the UTC offset
00369           double gps_seconds = position_sync_buffer_.front()->novatel_msg_header.gps_seconds + utc_offset_;
00370           if (gps_seconds < 0)
00371           {
00372               // Handle times around week boundaries
00373               gps_seconds = gps_seconds + 604800;  // 604800 = 7 * 24 * 60 * 60 (seconds in a week)
00374           }
00375           int32_t days = static_cast<int32_t>(gps_seconds / 86400.0);
00376           double position_time = gps_seconds - days * 86400.0;
00377 
00378           // Find the time difference between gpgga and position time
00379           double pos_dt = gpgga_time - position_time;
00380           // Handle times around midnight
00381           if (pos_dt > 43200.0)
00382           {
00383             pos_dt -= 86400.0;
00384           }
00385           if (pos_dt < -43200.0)
00386           {
00387             pos_dt += 86400.0;
00388           }
00389           if (pos_dt > gpgga_position_sync_tol_)
00390           {
00391             // The position message is more than tol older than the gpgga message,
00392             // discard it and continue
00393             ROS_DEBUG("Discarding a position message that is too old (%f < %f)", position_time, gpgga_time);
00394             position_sync_buffer_.pop_front();
00395           }
00396           else if (-pos_dt > gpgga_position_sync_tol_)
00397           {
00398             // The position message is more than tol ahead of the gpgga message,
00399             // use it but don't pop it
00400             ROS_DEBUG("Waiting because the most recent GPGGA message is too old (%f > %f)", position_time, gpgga_time);
00401             has_position = true;
00402             break;
00403           }
00404           else //the gpgga and position tol messages are in sync
00405           {
00406             has_position = true;
00407             pop_position = true;
00408             break;
00409           }
00410         }
00411 
00412         if (has_position || !wait_for_position_)
00413         {
00414           // If we have a position message (or don't need one), create and fill
00415           // a GPS fix message
00416           gps_common::GPSFixPtr gps_fix = boost::make_shared<gps_common::GPSFix>();
00417           // Fill GPS fix message using the messages at the front of the two
00418           // sync queues
00419           extractor_.GetGpsFixMessage(
00420               gprmc_sync_buffer_.front(),
00421               gpgga_sync_buffer_.front(),
00422               gps_fix);
00423 
00424           // Remove the used messages from the two sync queues
00425           gpgga_sync_buffer_.pop_front();
00426           gprmc_sync_buffer_.pop_front();
00427 
00428           if (has_position)
00429           {
00430             // We have a position message, so we can calculate variances
00431             // from the standard deviations
00432             double sigma_x = position_sync_buffer_.front()->lon_sigma;
00433             gps_fix->position_covariance[0] = sigma_x * sigma_x;
00434 
00435             double sigma_y = position_sync_buffer_.front()->lat_sigma;
00436             gps_fix->position_covariance[4] = sigma_y * sigma_y;
00437 
00438             double sigma_z = position_sync_buffer_.front()->height_sigma;
00439             gps_fix->position_covariance[8] = sigma_z * sigma_z;
00440 
00441             gps_fix->position_covariance_type =
00442                 gps_common::GPSFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
00443 
00444             if (pop_position)
00445             {
00446               position_sync_buffer_.pop_front();
00447             }
00448           }
00449 
00450           // Add the message to the fix message list
00451           fix_messages.push_back(gps_fix);
00452         }
00453         else  // There is no position message (and wait_for_position is true)
00454         {
00455           // return without pushing any more gps fix messages to the list
00456           return;
00457         }
00458       }  // else (gpgga and gprmc synced)
00459     }  // while (gpgga and gprmc buffers contain messages)
00460   }
00461 
00462   void  NovatelGps::GetNovatelHeading2Messages(std::vector<novatel_gps_msgs::NovatelHeading2Ptr>& headings) {
00463     headings.clear();
00464     headings.insert(headings.end(), heading2_msgs_.begin(), heading2_msgs_.end());
00465     heading2_msgs_.clear();
00466   }
00467 
00468   void  NovatelGps::GetNovatelDualAntennaHeadingMessages(std::vector<novatel_gps_msgs::NovatelDualAntennaHeadingPtr>& headings) {
00469     headings.clear();
00470     headings.insert(headings.end(), dual_antenna_heading_msgs_.begin(), dual_antenna_heading_msgs_.end());
00471     dual_antenna_heading_msgs_.clear();
00472   }
00473 
00474   void NovatelGps::GetNovatelCorrectedImuData(std::vector<novatel_gps_msgs::NovatelCorrectedImuDataPtr>& imu_messages)
00475   {
00476     imu_messages.clear();
00477     imu_messages.insert(imu_messages.end(), corrimudata_msgs_.begin(), corrimudata_msgs_.end());
00478     corrimudata_msgs_.clear();
00479   }
00480 
00481   void NovatelGps::GetGpggaMessages(std::vector<novatel_gps_msgs::GpggaPtr>& gpgga_messages)
00482   {
00483     gpgga_messages.clear();
00484     gpgga_messages.insert(gpgga_messages.end(), gpgga_msgs_.begin(), gpgga_msgs_.end());
00485     gpgga_msgs_.clear();
00486   }
00487 
00488   void NovatelGps::GetGpgsaMessages(std::vector<novatel_gps_msgs::GpgsaPtr>& gpgsa_messages)
00489   {
00490     gpgsa_messages.resize(gpgsa_msgs_.size());
00491     std::copy(gpgsa_msgs_.begin(), gpgsa_msgs_.end(), gpgsa_messages.begin());
00492     gpgsa_msgs_.clear();
00493   }
00494 
00495   void NovatelGps::GetGpgsvMessages(std::vector<novatel_gps_msgs::GpgsvPtr>& gpgsv_messages)
00496   {
00497     gpgsv_messages.resize(gpgsv_msgs_.size());
00498     std::copy(gpgsv_msgs_.begin(), gpgsv_msgs_.end(), gpgsv_messages.begin());
00499     gpgsv_msgs_.clear();
00500   }
00501 
00502   void NovatelGps::GetGprmcMessages(std::vector<novatel_gps_msgs::GprmcPtr>& gprmc_messages)
00503   {
00504     gprmc_messages.clear();
00505     gprmc_messages.insert(gprmc_messages.end(), gprmc_msgs_.begin(), gprmc_msgs_.end());
00506     gprmc_msgs_.clear();
00507   }
00508 
00509   void NovatelGps::GetInscovMessages(std::vector<novatel_gps_msgs::InscovPtr>& inscov_messages)
00510   {
00511     inscov_messages.clear();
00512     inscov_messages.insert(inscov_messages.end(), inscov_msgs_.begin(), inscov_msgs_.end());
00513     inscov_msgs_.clear();
00514   }
00515 
00516   void NovatelGps::GetInspvaMessages(std::vector<novatel_gps_msgs::InspvaPtr>& inspva_messages)
00517   {
00518     inspva_messages.clear();
00519     inspva_messages.insert(inspva_messages.end(), inspva_msgs_.begin(), inspva_msgs_.end());
00520     inspva_msgs_.clear();
00521   }
00522 
00523   void NovatelGps::GetInsstdevMessages(std::vector<novatel_gps_msgs::InsstdevPtr>& insstdev_messages)
00524   {
00525     insstdev_messages.clear();
00526     insstdev_messages.insert(insstdev_messages.end(), insstdev_msgs_.begin(), insstdev_msgs_.end());
00527     insstdev_msgs_.clear();
00528   }
00529 
00530   void NovatelGps::GetRangeMessages(std::vector<novatel_gps_msgs::RangePtr>& range_messages)
00531   {
00532     range_messages.resize(range_msgs_.size());
00533     std::copy(range_msgs_.begin(), range_msgs_.end(), range_messages.begin());
00534     range_msgs_.clear();
00535   }
00536 
00537   void NovatelGps::GetTimeMessages(std::vector<novatel_gps_msgs::TimePtr>& time_messages)
00538   {
00539     time_messages.resize(time_msgs_.size());
00540     std::copy(time_msgs_.begin(), time_msgs_.end(), time_messages.begin());
00541     time_msgs_.clear();
00542   }
00543 
00544   void NovatelGps::GetTrackstatMessages(std::vector<novatel_gps_msgs::TrackstatPtr>& trackstat_msgs)
00545   {
00546     trackstat_msgs.resize(trackstat_msgs_.size());
00547     std::copy(trackstat_msgs_.begin(), trackstat_msgs_.end(), trackstat_msgs.begin());
00548     trackstat_msgs_.clear();
00549   }
00550 
00551   void NovatelGps::GetClockSteeringMessages(std::vector<novatel_gps_msgs::ClockSteeringPtr>& clocksteering_msgs)
00552   {
00553     clocksteering_msgs.resize(clocksteering_msgs_.size());
00554     std::copy(clocksteering_msgs_.begin(), clocksteering_msgs_.end(), clocksteering_msgs.begin());
00555     clocksteering_msgs_.clear();
00556   }
00557 
00558   bool NovatelGps::CreatePcapConnection(const std::string& device, NovatelMessageOpts const& opts)
00559   {
00560     ROS_INFO("Opening pcap file: %s", device.c_str());
00561 
00562     if ((pcap_ = pcap_open_offline(device.c_str(), pcap_errbuf_)) == NULL)
00563     {
00564       ROS_FATAL("Unable to open pcap file.");
00565       return false;
00566     }
00567 
00568     pcap_compile(pcap_, &pcap_packet_filter_, "tcp dst port 3001", 1, PCAP_NETMASK_UNKNOWN);
00569     is_connected_ = true;
00570 
00571     return true;
00572   }
00573 
00574   bool NovatelGps::CreateSerialConnection(const std::string& device, NovatelMessageOpts const& opts)
00575   {
00576     swri_serial_util::SerialConfig config;
00577     config.baud = serial_baud_;
00578     config.parity = swri_serial_util::SerialConfig::NO_PARITY;
00579     config.flow_control = false;
00580     config.data_bits = 8;
00581     config.stop_bits = 1;
00582     config.low_latency_mode = false;
00583     config.writable = true; // Assume that we can write to this port
00584 
00585     bool success = serial_.Open(device, config);
00586 
00587     if (success)
00588     {
00589       is_connected_ = true;
00590       if (!Configure(opts))
00591       {
00592         // We will not kill the connection here, because the device may already
00593         // be setup to communicate correctly, but we will print a warning         
00594         ROS_ERROR("Failed to configure GPS. This port may be read only, or the "
00595                  "device may not be functioning as expected; however, the "
00596                  "driver may still function correctly if the port has already "
00597                  "been pre-configured.");
00598       }
00599     }
00600     else
00601     {
00602       error_msg_ = serial_.ErrorMsg();
00603     }
00604 
00605     return success;
00606   }
00607 
00608   bool NovatelGps::CreateIpConnection(const std::string& endpoint, NovatelMessageOpts const& opts)
00609   {
00610     std::string ip;
00611     std::string port;
00612     uint16_t num_port;
00613     size_t sep_pos = endpoint.find(':');
00614     if (sep_pos == std::string::npos || sep_pos == endpoint.size() - 1)
00615     {
00616       ROS_INFO("Using default port.");
00617       std::stringstream ss;
00618       if (connection_ == TCP)
00619       {
00620         num_port = DEFAULT_TCP_PORT;
00621       }
00622       else
00623       {
00624         num_port = DEFAULT_UDP_PORT;
00625       }
00626       ss << num_port;
00627       port = ss.str();
00628     }
00629     else
00630     {
00631       port = endpoint.substr(sep_pos + 1);
00632     }
00633 
00634     if (sep_pos != 0)
00635     {
00636       ip = endpoint.substr(0, sep_pos);
00637     }
00638 
00639     try
00640     {
00641       if (!ip.empty())
00642       {
00643         if (connection_ == TCP)
00644         {
00645           boost::asio::ip::tcp::resolver resolver(io_service_);
00646           boost::asio::ip::tcp::resolver::query query(ip, port);
00647           boost::asio::ip::tcp::resolver::iterator iter = resolver.resolve(query);
00648 
00649           boost::asio::connect(tcp_socket_, iter);
00650           ROS_INFO("Connecting via TCP to %s:%s", ip.c_str(), port.c_str());
00651         }
00652         else
00653         {
00654           boost::asio::ip::udp::resolver resolver(io_service_);
00655           boost::asio::ip::udp::resolver::query query(ip, port);
00656           udp_endpoint_ = boost::make_shared<boost::asio::ip::udp::endpoint>(*resolver.resolve(query));
00657           udp_socket_.reset(new boost::asio::ip::udp::socket(io_service_));
00658           udp_socket_->open(boost::asio::ip::udp::v4());
00659           ROS_INFO("Connecting via UDP to %s:%s", ip.c_str(), port.c_str());
00660         }
00661       }
00662       else
00663       {
00664         uint16_t port_num = static_cast<uint16_t>(strtoll(port.c_str(), NULL, 10));
00665         if (connection_ == TCP)
00666         {
00667           boost::asio::ip::tcp::acceptor acceptor(io_service_,
00668                                                   boost::asio::ip::tcp::endpoint(
00669                                                       boost::asio::ip::tcp::v4(), port_num));
00670           ROS_INFO("Listening on TCP port %s", port.c_str());
00671           acceptor.accept(tcp_socket_);
00672           ROS_INFO("Accepted TCP connection from client: %s",
00673                    tcp_socket_.remote_endpoint().address().to_string().c_str());
00674         }
00675         else
00676         {
00677           udp_socket_.reset(new boost::asio::ip::udp::socket(
00678               io_service_,
00679               boost::asio::ip::udp::endpoint(boost::asio::ip::udp::v4(),
00680                                              port_num)));
00681           boost::array<char, 1> recv_buf;
00682           udp_endpoint_ = boost::make_shared<boost::asio::ip::udp::endpoint>();
00683           boost::system::error_code error;
00684 
00685           ROS_INFO("Listening on UDP port %s", port.c_str());
00686           udp_socket_->receive_from(boost::asio::buffer(recv_buf), *udp_endpoint_, 0, error);
00687           if (error && error != boost::asio::error::message_size)
00688           {
00689             throw boost::system::system_error(error);
00690           }
00691 
00692           ROS_INFO("Accepted UDP connection from client: %s",
00693                    udp_endpoint_->address().to_string().c_str());
00694         }
00695       }
00696     }
00697     catch (std::exception& e)
00698     {
00699       error_msg_ = e.what();
00700       ROS_ERROR("Unable to connect: %s", e.what());
00701       return false;
00702     }
00703 
00704     is_connected_ = true;
00705 
00706     if (Configure(opts))
00707     {
00708       ROS_INFO("Configured GPS.");
00709     }
00710     else
00711     {
00712       // We will not kill the connection here, because the device may already
00713       // be setup to communicate correctly, but we will print a warning
00714       ROS_ERROR("Failed to configure GPS. This port may be read only, or the "
00715                    "device may not be functioning as expected; however, the "
00716                    "driver may still function correctly if the port has already "
00717                    "been pre-configured.");
00718     }
00719 
00720     return true;
00721   }
00722 
00723   NovatelGps::ReadResult NovatelGps::ReadData()
00724   {
00725     if (connection_ == SERIAL)
00726     {
00727       swri_serial_util::SerialPort::Result result =
00728           serial_.ReadBytes(data_buffer_, 0, 1000);
00729 
00730       if (result == swri_serial_util::SerialPort::ERROR)
00731       {
00732         error_msg_ = serial_.ErrorMsg();
00733         return READ_ERROR;
00734       }
00735       else if (result == swri_serial_util::SerialPort::TIMEOUT)
00736       {
00737         error_msg_ = "Timed out waiting for serial device.";
00738         return READ_TIMEOUT;
00739       }
00740       else if (result == swri_serial_util::SerialPort::INTERRUPTED)
00741       {
00742         error_msg_ = "Interrupted during read from serial device.";
00743         return READ_INTERRUPTED;
00744       }
00745 
00746       return READ_SUCCESS;
00747     }
00748     else if (connection_ == TCP || connection_ == UDP)
00749     {
00750       try
00751       {
00752         boost::system::error_code error;
00753         size_t len;
00754 
00755         if (connection_ == TCP)
00756         {
00757           len = tcp_socket_.read_some(boost::asio::buffer(socket_buffer_), error);
00758         }
00759         else
00760         {
00761           boost::asio::ip::udp::endpoint remote_endpoint;
00762           len = udp_socket_->receive_from(boost::asio::buffer(socket_buffer_), remote_endpoint);
00763         }
00764         data_buffer_.insert(data_buffer_.end(), socket_buffer_.begin(), socket_buffer_.begin()+len);
00765         if (error)
00766         {
00767           error_msg_ = error.message();
00768           Disconnect();
00769           return READ_ERROR;
00770         }
00771         return READ_SUCCESS;
00772       }
00773       catch (std::exception& e)
00774       {
00775         ROS_WARN("TCP connection error: %s", e.what());
00776       }
00777     }
00778     else if (connection_ == PCAP)
00779     {
00780       struct pcap_pkthdr* header;
00781       const u_char *pkt_data;
00782 
00783       int result;
00784       result = pcap_next_ex(pcap_, &header, &pkt_data);
00785       if (result >= 0)
00786       {
00787         struct iphdr* iph = (struct iphdr*)(pkt_data + sizeof(struct ethhdr));
00788         uint32_t iphdrlen = iph->ihl * 4;
00789 
00790         switch (iph->protocol)
00791         {
00792           case 6: // TCP
00793           {
00794             if (header->len == 54)
00795             {
00796               // Empty packet, skip it.
00797               return READ_SUCCESS;
00798             }
00799 
00800             // It's possible to get multiple subsequent TCP packets with the same seq
00801             // but latter ones have more data than previous ones.  In case that happens,
00802             // we need to only process the one with the most data.  We do that by
00803             // storing the most recently received message in a buffer, replacing it if
00804             // we get a new one with the same seq but more data, and only sending it to
00805             // the parser when we get a new packet with a different seq.
00806             // Note that when we copy data into last_tcp_packet_, we omit the ethernet
00807             // header because we don't care about it; we still need the IP and TCP
00808             // headers.  After we move it from last_tcp_packet_ into data_buffer, we
00809             // can skip the IP header and the TCP data offset.
00810             bool store_packet = true;
00811             if (!last_tcp_packet_.empty())
00812             {
00813               struct tcphdr* tcph = (struct tcphdr*) (pkt_data + iphdrlen + sizeof(struct ethhdr));
00814               struct iphdr* last_iph = (struct iphdr*) (&(last_tcp_packet_[0]));
00815               uint32_t last_iphdrlen = last_iph->ihl * 4;
00816               struct tcphdr* last_tcph = (struct tcphdr*) (&(last_tcp_packet_[0]) + last_iphdrlen);
00817               uint16_t last_len = ntohs(static_cast<uint16_t>(last_iph->tot_len));
00818               uint16_t new_len = ntohs(static_cast<uint16_t>(iph->tot_len));
00819               uint32_t last_seq = ntohl(last_tcph->seq);
00820               uint32_t new_seq = ntohl(tcph->seq);
00821 
00822               if (new_seq != last_seq)
00823               {
00824                 // If we got a packet that has a different seq than our previous one, send
00825                 // the previous one and store the new one.
00826                 uint32_t data_offset = last_tcph->doff * 4;
00827                 data_buffer_.insert(data_buffer_.end(),
00828                                     last_tcp_packet_.begin() + last_iphdrlen + data_offset,
00829                                     last_tcp_packet_.end());
00830               }
00831               else if (new_len <= last_len)
00832               {
00833                 // If we got a packet with the same seq as the previous one but it doesn't
00834                 // have more data, do nothing.
00835                 store_packet = false;
00836               }
00837             }
00838 
00839             if (store_packet)
00840             {
00841               // If we get here, we either just sent the previous packet, or we got
00842               // a new packet with the same seq but more data.  In either case,
00843               // store it.
00844               last_tcp_packet_.clear();
00845               last_tcp_packet_.insert(last_tcp_packet_.end(),
00846                                       pkt_data + sizeof(struct ethhdr),
00847                                       pkt_data + header->len);
00848             }
00849 
00850             break;
00851           }
00852           case 17: // UDP
00853           {
00854             uint16_t frag_off = ntohs(static_cast<uint16_t>(iph->frag_off));
00855             uint16_t fragment_offset = frag_off & static_cast<uint16_t>(0x1FFF);
00856             size_t header_size;
00857             // UDP packets may be fragmented; this isn't really "correct", but for
00858             // simplicity's sake we'll assume we get fragments in the right order.
00859             if (fragment_offset == 0)
00860             {
00861               header_size = sizeof(struct ethhdr) + iphdrlen + sizeof(struct udphdr);
00862             }
00863             else
00864             {
00865               header_size = sizeof(struct ethhdr) + iphdrlen;
00866             }
00867 
00868             data_buffer_.insert(data_buffer_.end(), pkt_data + header_size, pkt_data + header->len);
00869 
00870             break;
00871           }
00872           default:
00873             ROS_WARN("Unexpected protocol: %u", iph->protocol);
00874             return READ_ERROR;
00875         }
00876 
00877         // Add a slight delay after reading packets; if the node is being tested offline
00878         // and this loop is hammering the TCP, logs won't output properly.
00879         ros::Duration(0.001).sleep();
00880 
00881         return READ_SUCCESS;
00882       }
00883       else if (result == -2)
00884       {
00885         ROS_INFO("Done reading pcap file.");
00886         if (!last_tcp_packet_.empty())
00887         {
00888           // Don't forget to submit the last packet if we still have one!
00889           struct iphdr* last_iph = (struct iphdr*) (&(last_tcp_packet_[0]));
00890           uint32_t iphdrlen = last_iph->ihl * 4;
00891           struct tcphdr* last_tcph = (struct tcphdr*) (&(last_tcp_packet_[0]) + iphdrlen);
00892           uint32_t data_offset = last_tcph->doff * 4;
00893           data_buffer_.insert(data_buffer_.end(),
00894                               last_tcp_packet_.begin() + iphdrlen + data_offset,
00895                               last_tcp_packet_.end());
00896           last_tcp_packet_.clear();
00897         }
00898         Disconnect();
00899         return READ_SUCCESS;
00900       }
00901       else
00902       {
00903         ROS_WARN("Error reading pcap data: %s", pcap_geterr(pcap_));
00904         return READ_ERROR;
00905       }
00906     }
00907 
00908     error_msg_ = "Unsupported connection type.";
00909 
00910     return READ_ERROR;
00911   }
00912 
00913   void NovatelGps::GetImuMessages(std::vector<sensor_msgs::ImuPtr>& imu_messages)
00914   {
00915     imu_messages.clear();
00916     imu_messages.insert(imu_messages.end(), imu_msgs_.begin(), imu_msgs_.end());
00917     imu_msgs_.clear();
00918   }
00919 
00920   void NovatelGps::GenerateImuMessages()
00921   {
00922     if (imu_rate_ <= 0.0)
00923     {
00924       ROS_WARN_ONCE("IMU rate has not been configured; cannot produce sensor_msgs/Imu messages.");
00925       return;
00926     }
00927 
00928     if (!latest_insstdev_ && !latest_inscov_)
00929     {
00930       // If we haven't received an INSSTDEV or an INSCOV message, don't do anything, just return.
00931       ROS_WARN_THROTTLE(1.0, "No INSSTDEV or INSCOV data yet; orientation covariance will be unavailable.");
00932     }
00933 
00934     size_t previous_size = imu_msgs_.size();
00935     // Only do anything if we have both CORRIMUDATA and INSPVA messages.
00936     while (!corrimudata_queue_.empty() && !inspva_queue_.empty())
00937     {
00938       novatel_gps_msgs::NovatelCorrectedImuDataPtr corrimudata = corrimudata_queue_.front();
00939       novatel_gps_msgs::InspvaPtr inspva = inspva_queue_.front();
00940 
00941       double corrimudata_time = corrimudata->gps_week_num * SECONDS_PER_WEEK + corrimudata->gps_seconds;
00942       double inspva_time = inspva->novatel_msg_header.gps_week_num *
00943                                SECONDS_PER_WEEK + inspva->novatel_msg_header.gps_seconds;
00944 
00945       if (std::fabs(corrimudata_time - inspva_time) > IMU_TOLERANCE_S)
00946       {
00947         // If the two messages are too far apart to sync, discard the oldest one.
00948         ROS_DEBUG("INSPVA and CORRIMUDATA were unacceptably far apart.");
00949         if (corrimudata_time < inspva_time)
00950         {
00951           ROS_DEBUG("Discarding oldest CORRIMUDATA.");
00952           corrimudata_queue_.pop();
00953           continue;
00954         }
00955         else
00956         {
00957           ROS_DEBUG("Discarding oldest INSPVA.");
00958           inspva_queue_.pop();
00959           continue;
00960         }
00961       }
00962       // If we've successfully matched up two messages, remove them from their queues.
00963       inspva_queue_.pop();
00964       corrimudata_queue_.pop();
00965 
00966       // Now we can combine them together to make an Imu message.
00967       sensor_msgs::ImuPtr imu = boost::make_shared<sensor_msgs::Imu>();
00968 
00969       imu->header.stamp = corrimudata->header.stamp;
00970       imu->orientation = tf::createQuaternionMsgFromRollPitchYaw(inspva->roll * DEGREES_TO_RADIANS,
00971                                               -(inspva->pitch) * DEGREES_TO_RADIANS,
00972                                               -(inspva->azimuth) * DEGREES_TO_RADIANS);
00973 
00974       if (latest_inscov_)
00975       {
00976         imu->orientation_covariance = latest_inscov_->attitude_covariance;
00977       }
00978       else if (latest_insstdev_)
00979       {
00980         imu->orientation_covariance[0] = std::pow(2, latest_insstdev_->pitch_dev);
00981         imu->orientation_covariance[4] = std::pow(2, latest_insstdev_->roll_dev);
00982         imu->orientation_covariance[8] = std::pow(2, latest_insstdev_->azimuth_dev);
00983       }
00984       else
00985       {
00986         imu->orientation_covariance[0] =
00987         imu->orientation_covariance[4] =
00988         imu->orientation_covariance[8] = 1e-3;
00989       }
00990 
00991       imu->angular_velocity.x = corrimudata->pitch_rate * imu_rate_;
00992       imu->angular_velocity.y = corrimudata->roll_rate * imu_rate_;
00993       imu->angular_velocity.z = corrimudata->yaw_rate * imu_rate_;
00994       imu->angular_velocity_covariance[0] =
00995       imu->angular_velocity_covariance[4] =
00996       imu->angular_velocity_covariance[8] = 1e-3;
00997 
00998       imu->linear_acceleration.x = corrimudata->lateral_acceleration * imu_rate_;
00999       imu->linear_acceleration.y = corrimudata->longitudinal_acceleration * imu_rate_;
01000       imu->linear_acceleration.z = corrimudata->vertical_acceleration * imu_rate_;
01001       imu->linear_acceleration_covariance[0] =
01002       imu->linear_acceleration_covariance[4] =
01003       imu->linear_acceleration_covariance[8] = 1e-3;
01004 
01005       imu_msgs_.push_back(imu);
01006     }
01007 
01008     size_t new_size = imu_msgs_.size() - previous_size;
01009     ROS_DEBUG("Created %lu new sensor_msgs/Imu messages.", new_size);
01010   }
01011 
01012   void NovatelGps::SetImuRate(double imu_rate, bool imu_rate_forced)
01013   {
01014     ROS_INFO("IMU sample rate: %f", imu_rate);
01015     imu_rate_ = imu_rate;
01016     if (imu_rate_forced)
01017     {
01018       imu_rate_forced_ = true;
01019     }
01020   }
01021 
01022   void NovatelGps::SetSerialBaud(int32_t serial_baud)
01023   {
01024     ROS_INFO("Serial baud rate : %d", serial_baud);
01025     serial_baud_ = serial_baud;
01026   }
01027 
01028   NovatelGps::ReadResult NovatelGps::ParseBinaryMessage(const BinaryMessage& msg,
01029                                                         const ros::Time& stamp) throw(ParseException)
01030   {
01031     switch (msg.header_.message_id_)
01032     {
01033       case BestposParser::MESSAGE_ID:
01034       {
01035         novatel_gps_msgs::NovatelPositionPtr position = bestpos_parser_.ParseBinary(msg);
01036         position->header.stamp = stamp;
01037         novatel_positions_.push_back(position);
01038         position_sync_buffer_.push_back(position);
01039         break;
01040       }
01041       case BestxyzParser::MESSAGE_ID:
01042       {
01043         novatel_gps_msgs::NovatelXYZPtr xyz_position = bestxyz_parser_.ParseBinary(msg);
01044         xyz_position->header.stamp = stamp;
01045         novatel_xyz_positions_.push_back(xyz_position);
01046         break;
01047       }
01048       case BestutmParser::MESSAGE_ID:
01049       {
01050         novatel_gps_msgs::NovatelUtmPositionPtr utm_position = bestutm_parser_.ParseBinary(msg);
01051         utm_position->header.stamp = stamp;
01052         novatel_utm_positions_.push_back(utm_position);
01053         break;
01054       }
01055       case BestvelParser::MESSAGE_ID:
01056       {
01057         novatel_gps_msgs::NovatelVelocityPtr velocity = bestvel_parser_.ParseBinary(msg);
01058         velocity->header.stamp = stamp;
01059         novatel_velocities_.push_back(velocity);
01060         break;
01061       }
01062       case Heading2Parser::MESSAGE_ID:
01063       {
01064         novatel_gps_msgs::NovatelHeading2Ptr heading = heading2_parser_.ParseBinary(msg);
01065         heading->header.stamp = stamp;
01066         heading2_msgs_.push_back(heading);
01067         break;
01068       }
01069       case DualAntennaHeadingParser::MESSAGE_ID:
01070       {
01071         novatel_gps_msgs::NovatelDualAntennaHeadingPtr heading = dual_antenna_heading_parser_.ParseBinary(msg);
01072         heading->header.stamp = stamp;
01073         dual_antenna_heading_msgs_.push_back(heading);
01074         break;
01075       }
01076       case CorrImuDataParser::MESSAGE_ID:
01077       {
01078         novatel_gps_msgs::NovatelCorrectedImuDataPtr imu = corrimudata_parser_.ParseBinary(msg);
01079         imu->header.stamp = stamp;
01080         corrimudata_msgs_.push_back(imu);
01081         corrimudata_queue_.push(imu);
01082         if (corrimudata_queue_.size() > MAX_BUFFER_SIZE)
01083         {
01084           ROS_WARN_THROTTLE(1.0, "CORRIMUDATA queue overflow.");
01085           corrimudata_queue_.pop();
01086         }
01087         GenerateImuMessages();
01088         break;
01089       }
01090       case InscovParser::MESSAGE_ID:
01091       {
01092         novatel_gps_msgs::InscovPtr inscov = inscov_parser_.ParseBinary(msg);
01093         inscov->header.stamp = stamp;
01094         inscov_msgs_.push_back(inscov);
01095         latest_inscov_ = inscov;
01096         break;
01097       }
01098       case InspvaParser::MESSAGE_ID:
01099       {
01100         novatel_gps_msgs::InspvaPtr inspva = inspva_parser_.ParseBinary(msg);
01101         inspva->header.stamp = stamp;
01102         inspva_msgs_.push_back(inspva);
01103         inspva_queue_.push(inspva);
01104         if (inspva_queue_.size() > MAX_BUFFER_SIZE)
01105         {
01106           ROS_WARN_THROTTLE(1.0, "INSPVA queue overflow.");
01107           inspva_queue_.pop();
01108         }
01109         GenerateImuMessages();
01110         break;
01111       }
01112       case InsstdevParser::MESSAGE_ID:
01113       {
01114         novatel_gps_msgs::InsstdevPtr insstdev = insstdev_parser_.ParseBinary(msg);
01115         insstdev->header.stamp = stamp;
01116         insstdev_msgs_.push_back(insstdev);
01117         latest_insstdev_ = insstdev;
01118         break;
01119       }
01120       case RangeParser::MESSAGE_ID:
01121       {
01122         novatel_gps_msgs::RangePtr range = range_parser_.ParseBinary(msg);
01123         range->header.stamp = stamp;
01124         range_msgs_.push_back(range);
01125         break;
01126       }
01127       case TimeParser::MESSAGE_ID:
01128       {
01129         novatel_gps_msgs::TimePtr time = time_parser_.ParseBinary(msg);
01130         utc_offset_ = time->utc_offset;
01131         ROS_DEBUG("Got a new TIME with offset %f. UTC offset is %f", time->utc_offset, utc_offset_);
01132         time->header.stamp = stamp;
01133         time_msgs_.push_back(time);
01134         break;
01135       }
01136       case TrackstatParser::MESSAGE_ID:
01137       {
01138         novatel_gps_msgs::TrackstatPtr trackstat = trackstat_parser_.ParseBinary(msg);
01139         trackstat->header.stamp = stamp;
01140         trackstat_msgs_.push_back(trackstat);
01141         break;
01142       }
01143       default:
01144         ROS_WARN("Unexpected binary message id: %u", msg.header_.message_id_);
01145         break;
01146     }
01147 
01148     return READ_SUCCESS;
01149   }
01150 
01151   NovatelGps::ReadResult NovatelGps::ParseNmeaSentence(const NmeaSentence& sentence,
01152                                                        const ros::Time& stamp,
01153                                                        double most_recent_utc_time) throw(ParseException)
01154   {
01155     if (sentence.id == GpggaParser::MESSAGE_NAME)
01156     {
01157       novatel_gps_msgs::GpggaPtr gpgga = gpgga_parser_.ParseAscii(sentence);
01158 
01159       if (most_recent_utc_time < gpgga->utc_seconds)
01160       {
01161         most_recent_utc_time = gpgga->utc_seconds;
01162       }
01163 
01164       gpgga->header.stamp = stamp - ros::Duration(most_recent_utc_time - gpgga->utc_seconds);
01165 
01166       if (gpgga_parser_.WasLastGpsValid())
01167       {
01168         gpgga_msgs_.push_back(gpgga);
01169 
01170         // Make a deep copy for the sync buffer so the GPSFix messages
01171         // don't get adjusted multiple times for the sync offset.
01172         gpgga_sync_buffer_.push_back(*gpgga);
01173       }
01174       else
01175       {
01176         gpgga_msgs_.push_back(gpgga);
01177       }
01178     }
01179     else if (sentence.id == GprmcParser::MESSAGE_NAME)
01180     {
01181       novatel_gps_msgs::GprmcPtr gprmc = gprmc_parser_.ParseAscii(sentence);
01182 
01183       if (most_recent_utc_time < gprmc->utc_seconds)
01184       {
01185         most_recent_utc_time = gprmc->utc_seconds;
01186       }
01187 
01188       gprmc->header.stamp = stamp - ros::Duration(most_recent_utc_time - gprmc->utc_seconds);
01189 
01190       if (gprmc_parser_.WasLastGpsValid())
01191       {
01192         gprmc_msgs_.push_back(gprmc);
01193 
01194         // Make a deep copy for the sync buffer so the GPSFix messages
01195         // don't get adjusted multiple times for the sync offset.
01196         gprmc_sync_buffer_.push_back(*gprmc);
01197       }
01198       else
01199       {
01200         gprmc_msgs_.push_back(gprmc);
01201       }
01202     }
01203     else if (sentence.id == GpgsaParser::MESSAGE_NAME)
01204     {
01205       novatel_gps_msgs::GpgsaPtr gpgsa = gpgsa_parser_.ParseAscii(sentence);
01206       gpgsa_msgs_.push_back(gpgsa);
01207     }
01208     else if (sentence.id == GpgsvParser::MESSAGE_NAME)
01209     {
01210       novatel_gps_msgs::GpgsvPtr gpgsv = gpgsv_parser_.ParseAscii(sentence);
01211       gpgsv_msgs_.push_back(gpgsv);
01212     }
01213     else
01214     {
01215       ROS_DEBUG_STREAM("Unrecognized NMEA sentence " << sentence.id);
01216     }
01217 
01218     return READ_SUCCESS;
01219   }
01220 
01221   NovatelGps::ReadResult NovatelGps::ParseNovatelSentence(const NovatelSentence& sentence,
01222                                                           const ros::Time& stamp) throw(ParseException)
01223   {
01224     if (sentence.id == "BESTPOSA")
01225     {
01226       novatel_gps_msgs::NovatelPositionPtr position = bestpos_parser_.ParseAscii(sentence);
01227       position->header.stamp = stamp;
01228       novatel_positions_.push_back(position);
01229       position_sync_buffer_.push_back(position);
01230     }
01231     else if (sentence.id == "BESTXYZ")
01232     {
01233       novatel_gps_msgs::NovatelXYZPtr position = bestxyz_parser_.ParseAscii(sentence);
01234       position->header.stamp = stamp;
01235       novatel_xyz_positions_.push_back(position);
01236     }
01237     else if (sentence.id == "BESTUTMA")
01238     {
01239       novatel_gps_msgs::NovatelUtmPositionPtr utm_position = bestutm_parser_.ParseAscii(sentence);
01240       utm_position->header.stamp = stamp;
01241       novatel_utm_positions_.push_back(utm_position);
01242     }
01243     else if (sentence.id == "BESTVELA")
01244     {
01245       novatel_gps_msgs::NovatelVelocityPtr velocity = bestvel_parser_.ParseAscii(sentence);
01246       velocity->header.stamp = stamp;
01247       novatel_velocities_.push_back(velocity);
01248     }
01249     else if (sentence.id == "HEADING2")
01250     {
01251       novatel_gps_msgs::NovatelHeading2Ptr heading = heading2_parser_.ParseAscii(sentence);
01252       heading->header.stamp = stamp;
01253       heading2_msgs_.push_back(heading);
01254     }
01255     else if (sentence.id == "DUALANTENNAHEADING")
01256     {
01257       novatel_gps_msgs::NovatelDualAntennaHeadingPtr heading = dual_antenna_heading_parser_.ParseAscii(sentence);
01258       heading->header.stamp = stamp;
01259       dual_antenna_heading_msgs_.push_back(heading);
01260     }
01261     else if (sentence.id == "CORRIMUDATAA")
01262     {
01263       novatel_gps_msgs::NovatelCorrectedImuDataPtr imu = corrimudata_parser_.ParseAscii(sentence);
01264       imu->header.stamp = stamp;
01265       corrimudata_msgs_.push_back(imu);
01266       corrimudata_queue_.push(imu);
01267       if (corrimudata_queue_.size() > MAX_BUFFER_SIZE)
01268       {
01269         ROS_WARN_THROTTLE(1.0, "CORRIMUDATA queue overflow.");
01270         corrimudata_queue_.pop();
01271       }
01272       GenerateImuMessages();
01273     }
01274     else if (sentence.id == "INSCOVA")
01275     {
01276       novatel_gps_msgs::InscovPtr inscov = inscov_parser_.ParseAscii(sentence);
01277       inscov->header.stamp = stamp;
01278       inscov_msgs_.push_back(inscov);
01279       latest_inscov_ = inscov;
01280     }
01281     else if (sentence.id == "INSPVAA")
01282     {
01283       novatel_gps_msgs::InspvaPtr inspva = inspva_parser_.ParseAscii(sentence);
01284       inspva->header.stamp = stamp;
01285       inspva_msgs_.push_back(inspva);
01286       inspva_queue_.push(inspva);
01287       if (inspva_queue_.size() > MAX_BUFFER_SIZE)
01288       {
01289         ROS_WARN_THROTTLE(1.0, "INSPVA queue overflow.");
01290         inspva_queue_.pop();
01291       }
01292       GenerateImuMessages();
01293     }
01294     else if (sentence.id == "INSSTDEVA")
01295     {
01296       novatel_gps_msgs::InsstdevPtr insstdev = insstdev_parser_.ParseAscii(sentence);
01297       insstdev->header.stamp = stamp;
01298       insstdev_msgs_.push_back(insstdev);
01299       latest_insstdev_ = insstdev;
01300     }
01301     else if (sentence.id == "TIMEA")
01302     {
01303       novatel_gps_msgs::TimePtr time = time_parser_.ParseAscii(sentence);
01304       utc_offset_ = time->utc_offset;
01305       ROS_DEBUG("Got a new TIME with offset %f. UTC offset is %f", time->utc_offset, utc_offset_);
01306       time->header.stamp = stamp;
01307       time_msgs_.push_back(time);
01308     }
01309     else if (sentence.id == "RANGEA")
01310     {
01311       novatel_gps_msgs::RangePtr range = range_parser_.ParseAscii(sentence);
01312       range->header.stamp = stamp;
01313       range_msgs_.push_back(range);
01314     }
01315     else if (sentence.id == "TRACKSTATA")
01316     {
01317       novatel_gps_msgs::TrackstatPtr trackstat = trackstat_parser_.ParseAscii(sentence);
01318       trackstat->header.stamp = stamp;
01319       trackstat_msgs_.push_back(trackstat);
01320     }
01321     else if (sentence.id == "RAWIMUXA")
01322     {
01323       static std::map<std::string, std::pair<double, std::string>> rates = {
01324         { "0",  std::pair<double, std::string>(100, "Unknown") },
01325         { "1",  std::pair<double, std::string>(100, "Honeywell HG1700 AG11") },
01326         { "4",  std::pair<double, std::string>(100, "Honeywell HG1700 AG17") },
01327         { "5",  std::pair<double, std::string>(100, "Honeywell HG1700 CA29") },
01328         { "8",  std::pair<double, std::string>(200, "Litton LN-200 (200hz model)") },
01329         { "11", std::pair<double, std::string>(100, "Honeywell HG1700 AG58") },
01330         { "12", std::pair<double, std::string>(100, "Honeywell HG1700 AG62") },
01331         { "13", std::pair<double, std::string>(200, "iMAR ilMU-FSAS") },
01332         { "16", std::pair<double, std::string>(200, "KVH 1750 IMU") },
01333         { "19", std::pair<double, std::string>(200, "Northrop Grumman Litef LCI-1") },
01334         { "20", std::pair<double, std::string>(100, "Honeywell HG1930 AA99") },
01335         { "26", std::pair<double, std::string>(100, "Northrop Grumman Litef ISA-100C") },
01336         { "27", std::pair<double, std::string>(100, "Honeywell HG1900 CA50") },
01337         { "28", std::pair<double, std::string>(100, "Honeywell HG1930 CA50") },
01338         { "31", std::pair<double, std::string>(200, "Analog Devices ADIS16488") },
01339         { "32", std::pair<double, std::string>(125, "Sensonor STIM300") },
01340         { "33", std::pair<double, std::string>(200, "KVH1750 IMU") },
01341         { "34", std::pair<double, std::string>(200, "Northrop Grumman Litef ISA-100") },
01342         { "38", std::pair<double, std::string>(400, "Northrop Grumman Litef ISA-100 400Hz") },
01343         { "39", std::pair<double, std::string>(400, "Northrop Grumman Litef ISA-100C 400Hz") },
01344         { "41", std::pair<double, std::string>(125, "Epson G320N") },
01345         { "45", std::pair<double, std::string>(200, "KVH 1725 IMU?") }, //(This was a guess based on the 1750
01346                        // as the actual rate is not documented and the specs are similar)
01347         { "52", std::pair<double, std::string>(200, "Litef microIMU") },
01348         { "56", std::pair<double, std::string>(125, "Sensonor STIM300, Direct Connection") },
01349         { "58", std::pair<double, std::string>(200, "Honeywell HG4930 AN01") },
01350        };
01351       
01352       // Parse out the IMU type then save it, we don't care about the rest (3rd field)
01353       std::string id = sentence.body.size() > 1 ? sentence.body[1] : "";
01354       if (rates.find(id) != rates.end())
01355       {
01356         double rate = rates[id].first;
01357  
01358         ROS_INFO("IMU Type %s Found, Rate: %f Hz", rates[id].second.c_str(), (float)rate);
01359         
01360         // Set the rate only if it hasnt been forced already
01361         if (imu_rate_forced_ == false)
01362         {        
01363           SetImuRate(rate, false); // Dont force set from here so it can be configured elsewhere
01364         }
01365       }
01366       else
01367       {
01368         // Error because the imu type was unknown
01369         ROS_ERROR("Unknown IMU Type Received: %s", id.c_str());
01370       }
01371     }
01372     else if (sentence.id == "CLOCKSTEERINGA")
01373     {
01374       novatel_gps_msgs::ClockSteeringPtr clocksteering = clocksteering_parser_.ParseAscii(sentence);
01375       clocksteering_msgs_.push_back(clocksteering);
01376     }
01377 
01378     return READ_SUCCESS;
01379   }
01380 
01381   bool NovatelGps::Write(const std::string& command)
01382   {
01383     std::vector<uint8_t> bytes(command.begin(), command.end());
01384 
01385     if (connection_ == SERIAL)
01386     {
01387       int32_t written = serial_.Write(bytes);
01388       if (written != (int32_t)command.length())
01389       {
01390         ROS_ERROR("Failed to send command: %s", command.c_str());
01391       }
01392       return written == (int32_t)command.length();
01393     }
01394     else if (connection_ == TCP || connection_ == UDP)
01395     {
01396       boost::system::error_code error;
01397       try
01398       {
01399         size_t written;
01400         if (connection_ == TCP)
01401         {
01402           written = boost::asio::write(tcp_socket_, boost::asio::buffer(bytes), error);
01403         }
01404         else
01405         {
01406           written = udp_socket_->send_to(boost::asio::buffer(bytes), *udp_endpoint_, 0, error);
01407         }
01408         if (error)
01409         {
01410           ROS_ERROR("Error writing TCP data: %s", error.message().c_str());
01411           Disconnect();
01412         }
01413         ROS_DEBUG("Wrote %lu bytes.", written);
01414         return written == (int32_t) command.length();
01415       }
01416       catch (std::exception& e)
01417       {
01418         Disconnect();
01419         ROS_ERROR("Exception writing TCP data: %s", e.what());
01420       }
01421     }
01422     else if (connection_ == PCAP)
01423     {
01424       ROS_WARN_ONCE("Writing data is unsupported in pcap mode.");
01425       return true;
01426     }
01427 
01428     return false;
01429   }
01430 
01431   bool NovatelGps::Configure(NovatelMessageOpts const& opts)
01432   {
01433     bool configured = true;
01434     configured = configured && Write("unlogall THISPORT_ALL\r\n");
01435 
01436     if (apply_vehicle_body_rotation_)
01437     {
01438       configured = configured && Write("vehiclebodyrotation 0 0 90\r\n");
01439       configured = configured && Write("applyvehiclebodyrotation\r\n");
01440     }
01441 
01442     for(NovatelMessageOpts::const_iterator option = opts.begin(); option != opts.end(); ++option)
01443     {
01444       std::stringstream command;
01445       command << std::setprecision(3);
01446       command << "log " << option->first << " ontime " << option->second << "\r\n";
01447       configured = configured && Write(command.str());
01448     }
01449 
01450     // Log the IMU data once to get the IMU type
01451     configured = configured && Write("log rawimuxa\r\n");
01452 
01453     return configured;
01454   }
01455 }


novatel_gps_driver
Author(s):
autogenerated on Wed Jul 3 2019 19:40:37