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       tcp_socket_(io_service_),
00053       pcap_(NULL),
00054       corrimudata_msgs_(MAX_BUFFER_SIZE),
00055       gpgga_msgs_(MAX_BUFFER_SIZE),
00056       gpgga_sync_buffer_(SYNC_BUFFER_SIZE),
00057       gpgsa_msgs_(MAX_BUFFER_SIZE),
00058       gpgsv_msgs_(MAX_BUFFER_SIZE),
00059       gprmc_msgs_(MAX_BUFFER_SIZE),
00060       gprmc_sync_buffer_(SYNC_BUFFER_SIZE),
00061       imu_msgs_(MAX_BUFFER_SIZE),
00062       inscov_msgs_(MAX_BUFFER_SIZE),
00063       inspva_msgs_(MAX_BUFFER_SIZE),
00064       insstdev_msgs_(MAX_BUFFER_SIZE),
00065       novatel_positions_(MAX_BUFFER_SIZE),
00066       novatel_velocities_(MAX_BUFFER_SIZE),
00067       position_sync_buffer_(SYNC_BUFFER_SIZE),
00068       range_msgs_(MAX_BUFFER_SIZE),
00069       time_msgs_(MAX_BUFFER_SIZE),
00070       trackstat_msgs_(MAX_BUFFER_SIZE),
00071       imu_rate_(-1.0)
00072   {
00073   }
00074 
00075   NovatelGps::~NovatelGps()
00076   {
00077     Disconnect();
00078   }
00079 
00080   bool NovatelGps::Connect(
00081       const std::string& device,
00082       ConnectionType connection)
00083   {
00084     NovatelMessageOpts opts;
00085     opts["gpgga"] = 0.05;
00086     opts["gprmc"] = 0.05;
00087     opts["bestposa"] = 0.05;
00088     opts["timea"] = 1.0;
00089     opts["rangea"] = 1;
00090     return Connect(device, connection, opts);
00091   }
00092 
00093   bool NovatelGps::Connect(
00094       const std::string& device,
00095       ConnectionType connection,
00096       NovatelMessageOpts const& opts)
00097   {
00098     Disconnect();
00099 
00100     connection_ = connection;
00101 
00102     if (connection_ == SERIAL)
00103     {
00104       return CreateSerialConnection(device, opts);
00105     }
00106     else if (connection_ == TCP || connection_ == UDP)
00107     {
00108       return CreateIpConnection(device, opts);
00109     }
00110     else if (connection_ == PCAP)
00111     {
00112       return CreatePcapConnection(device, opts);
00113     }
00114 
00115     error_msg_ = "Invalid connection type.";
00116 
00117     return false;
00118 
00119   }
00120 
00121   NovatelGps::ConnectionType NovatelGps::ParseConnection(const std::string& connection)
00122   {
00123     if (connection == "serial")
00124     {
00125       return SERIAL;
00126     }
00127     else if (connection == "udp")
00128     {
00129       return UDP;
00130     }
00131     else if (connection == "tcp")
00132     {
00133       return TCP;
00134     }
00135     else if (connection == "pcap")
00136     {
00137       return PCAP;
00138     }
00139 
00140     return INVALID;
00141   }
00142 
00143   void NovatelGps::Disconnect()
00144   {
00145     if (connection_ == SERIAL)
00146     {
00147       serial_.Close();
00148     }
00149     else if (connection_ == TCP)
00150     {
00151       tcp_socket_.close();
00152     }
00153     else if (connection_ == UDP)
00154     {
00155       if (udp_socket_)
00156       {
00157         udp_socket_->close();
00158         udp_socket_.reset();
00159       }
00160       if (udp_endpoint_)
00161       {
00162         udp_endpoint_.reset();
00163       }
00164     }
00165     else if (connection_ == PCAP)
00166     {
00167       if (pcap_ != NULL)
00168       {
00169         pcap_close(pcap_);
00170         pcap_ = NULL;
00171       }
00172     }
00173     is_connected_ = false;
00174   }
00175 
00176   NovatelGps::ReadResult NovatelGps::ProcessData()
00177   {
00178     NovatelGps::ReadResult read_result = ReadData();
00179 
00180     if (read_result != READ_SUCCESS)
00181     {
00182       return read_result;
00183     }
00184 
00185     ros::Time stamp = ros::Time::now();
00186     std::vector<NmeaSentence> nmea_sentences;
00187     std::vector<NovatelSentence> novatel_sentences;
00188     std::vector<BinaryMessage> binary_messages;
00189 
00190     if (!data_buffer_.empty())
00191     {
00192       nmea_buffer_.insert(nmea_buffer_.end(),
00193                           data_buffer_.begin(),
00194                           data_buffer_.end());
00195 
00196       data_buffer_.clear();
00197 
00198       std::string remaining_buffer;
00199 
00200       if (!extractor_.ExtractCompleteMessages(
00201           nmea_buffer_,
00202           nmea_sentences,
00203           novatel_sentences,
00204           binary_messages,
00205           remaining_buffer))
00206       {
00207         read_result = READ_PARSE_FAILED;
00208         error_msg_ = "Parse failure extracting sentences.";
00209       }
00210 
00211       nmea_buffer_ = remaining_buffer;
00212 
00213       ROS_DEBUG("Parsed: %lu NMEA / %lu NovAtel / %lu Binary messages",
00214                nmea_sentences.size(), novatel_sentences.size(), binary_messages.size());
00215       if (!nmea_buffer_.empty())
00216       {
00217         ROS_DEBUG("%lu unparsed bytes left over.", nmea_buffer_.size());
00218       }
00219     }
00220 
00221     double most_recent_utc_time = extractor_.GetMostRecentUtcTime(nmea_sentences);
00222 
00223     for(const auto& sentence : nmea_sentences)
00224     {
00225       try
00226       {
00227         NovatelGps::ReadResult result = ParseNmeaSentence(sentence, stamp, most_recent_utc_time);
00228         if (result != READ_SUCCESS)
00229         {
00230           read_result = result;
00231         }
00232       }
00233       catch (const ParseException& p)
00234       {
00235         error_msg_ = p.what();
00236         ROS_WARN("%s", p.what());
00237         ROS_WARN("For sentence: [%s]", boost::algorithm::join(sentence.body, ",").c_str());
00238         read_result = READ_PARSE_FAILED;
00239       }
00240     }
00241 
00242     for(const auto& sentence : novatel_sentences)
00243     {
00244       try
00245       {
00246         NovatelGps::ReadResult result = ParseNovatelSentence(sentence, stamp);
00247         if (result != READ_SUCCESS)
00248         {
00249           read_result = result;
00250         }
00251       }
00252       catch (const ParseException& p)
00253       {
00254         error_msg_ = p.what();
00255         ROS_WARN("%s", p.what());
00256         read_result = READ_PARSE_FAILED;
00257       }
00258     }
00259 
00260     for(const auto& msg : binary_messages)
00261     {
00262       try
00263       {
00264         NovatelGps::ReadResult result = ParseBinaryMessage(msg, stamp);
00265         if (result != READ_SUCCESS)
00266         {
00267           read_result = result;
00268         }
00269       }
00270       catch (const ParseException& p)
00271       {
00272         error_msg_ = p.what();
00273         ROS_WARN("%s", p.what());
00274         read_result = READ_PARSE_FAILED;
00275       }
00276     }
00277 
00278     return read_result;
00279   }
00280 
00281   void NovatelGps::GetNovatelPositions(std::vector<novatel_gps_msgs::NovatelPositionPtr>& positions)
00282   {
00283     positions.clear();
00284     positions.insert(positions.end(), novatel_positions_.begin(), novatel_positions_.end());
00285     novatel_positions_.clear();
00286   }
00287 
00288   void NovatelGps::GetNovatelVelocities(std::vector<novatel_gps_msgs::NovatelVelocityPtr>& velocities)
00289   {
00290     velocities.resize(novatel_velocities_.size());
00291     std::copy(novatel_velocities_.begin(), novatel_velocities_.end(), velocities.begin());
00292     novatel_velocities_.clear();
00293   }
00294 
00295   void NovatelGps::GetFixMessages(std::vector<gps_common::GPSFixPtr>& fix_messages)
00296   {
00297     // Clear out the fix_messages list before filling it
00298     fix_messages.clear();
00299 
00300     // both a gpgga and a gprmc message are required to fill the GPSFix message
00301     while (!gpgga_sync_buffer_.empty() && !gprmc_sync_buffer_.empty())
00302     {
00303       double gpgga_time = gpgga_sync_buffer_.front().utc_seconds;
00304       double gprmc_time = gprmc_sync_buffer_.front().utc_seconds;
00305 
00306       // Find the time difference between gpgga and gprmc time
00307       double dt = gpgga_time - gprmc_time;
00308       // Handle times around midnight
00309       if (dt > 43200.0)
00310       {
00311         dt -= 86400.0;
00312       }
00313       if (dt < -43200.0)
00314       {
00315         dt += 86400.0;
00316       }
00317 
00318       // Get the front elements of the gpgga and gprmc buffers synced to within tolerance
00319       if (dt > gpgga_gprmc_sync_tol_)
00320       {
00321         // The gprmc message is more than tol older than the gpgga message,
00322         // discard it and continue
00323         gprmc_sync_buffer_.pop_front();
00324       }
00325       else if (-dt > gpgga_gprmc_sync_tol_)
00326       {
00327         // The gpgga message is more than tol older than the gprmc message,
00328         // discard it and continue
00329         gpgga_sync_buffer_.pop_front();
00330       }
00331       else // The gpgga and gprmc messages are synced
00332       {
00333         bool has_position = false;
00334         bool pop_position = false;
00335 
00336         // Iterate over the position message buffer until we find one
00337         // that is synced with the gpgga message
00338         while (!position_sync_buffer_.empty())
00339         {
00340           // Calculate UTC position time from GPS seconds by subtracting out
00341           // full days and applying the UTC offset
00342           double gps_seconds = position_sync_buffer_.front()->novatel_msg_header.gps_seconds + utc_offset_;
00343           if (gps_seconds < 0)
00344           {
00345               // Handle times around week boundaries
00346               gps_seconds = gps_seconds + 604800;  // 604800 = 7 * 24 * 60 * 60 (seconds in a week)
00347           }
00348           int32_t days = static_cast<int32_t>(gps_seconds / 86400.0);
00349           double position_time = gps_seconds - days * 86400.0;
00350 
00351           // Find the time difference between gpgga and position time
00352           double pos_dt = gpgga_time - position_time;
00353           // Handle times around midnight
00354           if (pos_dt > 43200.0)
00355           {
00356             pos_dt -= 86400.0;
00357           }
00358           if (pos_dt < -43200.0)
00359           {
00360             pos_dt += 86400.0;
00361           }
00362           if (pos_dt > gpgga_position_sync_tol_)
00363           {
00364             // The position message is more than tol older than the gpgga message,
00365             // discard it and continue
00366             ROS_DEBUG("Discarding a position message that is too old (%f < %f)", position_time, gpgga_time);
00367             position_sync_buffer_.pop_front();
00368           }
00369           else if (-pos_dt > gpgga_position_sync_tol_)
00370           {
00371             // The position message is more than tol ahead of the gpgga message,
00372             // use it but don't pop it
00373             ROS_DEBUG("Waiting because the most recent GPGGA message is too old (%f > %f)", position_time, gpgga_time);
00374             has_position = true;
00375             break;
00376           }
00377           else //the gpgga and position tol messages are in sync
00378           {
00379             has_position = true;
00380             pop_position = true;
00381             break;
00382           }
00383         }
00384 
00385         if (has_position || !wait_for_position_)
00386         {
00387           // If we have a position message (or don't need one), create and fill
00388           // a GPS fix message
00389           gps_common::GPSFixPtr gps_fix = boost::make_shared<gps_common::GPSFix>();
00390           // Fill GPS fix message using the messages at the front of the two
00391           // sync queues
00392           extractor_.GetGpsFixMessage(
00393               gprmc_sync_buffer_.front(),
00394               gpgga_sync_buffer_.front(),
00395               gps_fix);
00396 
00397           // Remove the used messages from the two sync queues
00398           gpgga_sync_buffer_.pop_front();
00399           gprmc_sync_buffer_.pop_front();
00400 
00401           if (has_position)
00402           {
00403             // We have a position message, so we can calculate variances
00404             // from the standard deviations
00405             double sigma_x = position_sync_buffer_.front()->lon_sigma;
00406             gps_fix->position_covariance[0] = sigma_x * sigma_x;
00407 
00408             double sigma_y = position_sync_buffer_.front()->lat_sigma;
00409             gps_fix->position_covariance[4] = sigma_y * sigma_y;
00410 
00411             double sigma_z = position_sync_buffer_.front()->height_sigma;
00412             gps_fix->position_covariance[8] = sigma_z * sigma_z;
00413 
00414             gps_fix->position_covariance_type =
00415                 gps_common::GPSFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
00416 
00417             if (pop_position)
00418             {
00419               position_sync_buffer_.pop_front();
00420             }
00421           }
00422 
00423           // Add the message to the fix message list
00424           fix_messages.push_back(gps_fix);
00425         }
00426         else  // There is no position message (and wait_for_position is true)
00427         {
00428           // return without pushing any more gps fix messages to the list
00429           return;
00430         }
00431       }  // else (gpgga and gprmc synced)
00432     }  // while (gpgga and gprmc buffers contain messages)
00433   }
00434 
00435   void NovatelGps::GetNovatelCorrectedImuData(std::vector<novatel_gps_msgs::NovatelCorrectedImuDataPtr>& imu_messages)
00436   {
00437     imu_messages.clear();
00438     imu_messages.insert(imu_messages.end(), corrimudata_msgs_.begin(), corrimudata_msgs_.end());
00439     corrimudata_msgs_.clear();
00440   }
00441 
00442   void NovatelGps::GetGpggaMessages(std::vector<novatel_gps_msgs::GpggaPtr>& gpgga_messages)
00443   {
00444     gpgga_messages.clear();
00445     gpgga_messages.insert(gpgga_messages.end(), gpgga_msgs_.begin(), gpgga_msgs_.end());
00446     gpgga_msgs_.clear();
00447   }
00448 
00449   void NovatelGps::GetGpgsaMessages(std::vector<novatel_gps_msgs::GpgsaPtr>& gpgsa_messages)
00450   {
00451     gpgsa_messages.resize(gpgsa_msgs_.size());
00452     std::copy(gpgsa_msgs_.begin(), gpgsa_msgs_.end(), gpgsa_messages.begin());
00453     gpgsa_msgs_.clear();
00454   }
00455 
00456   void NovatelGps::GetGpgsvMessages(std::vector<novatel_gps_msgs::GpgsvPtr>& gpgsv_messages)
00457   {
00458     gpgsv_messages.resize(gpgsv_msgs_.size());
00459     std::copy(gpgsv_msgs_.begin(), gpgsv_msgs_.end(), gpgsv_messages.begin());
00460     gpgsv_msgs_.clear();
00461   }
00462 
00463   void NovatelGps::GetGprmcMessages(std::vector<novatel_gps_msgs::GprmcPtr>& gprmc_messages)
00464   {
00465     gprmc_messages.clear();
00466     gprmc_messages.insert(gprmc_messages.end(), gprmc_msgs_.begin(), gprmc_msgs_.end());
00467     gprmc_msgs_.clear();
00468   }
00469 
00470   void NovatelGps::GetInscovMessages(std::vector<novatel_gps_msgs::InscovPtr>& inscov_messages)
00471   {
00472     inscov_messages.clear();
00473     inscov_messages.insert(inscov_messages.end(), inscov_msgs_.begin(), inscov_msgs_.end());
00474     inscov_msgs_.clear();
00475   }
00476 
00477   void NovatelGps::GetInspvaMessages(std::vector<novatel_gps_msgs::InspvaPtr>& inspva_messages)
00478   {
00479     inspva_messages.clear();
00480     inspva_messages.insert(inspva_messages.end(), inspva_msgs_.begin(), inspva_msgs_.end());
00481     inspva_msgs_.clear();
00482   }
00483 
00484   void NovatelGps::GetInsstdevMessages(std::vector<novatel_gps_msgs::InsstdevPtr>& insstdev_messages)
00485   {
00486     insstdev_messages.clear();
00487     insstdev_messages.insert(insstdev_messages.end(), insstdev_msgs_.begin(), insstdev_msgs_.end());
00488     insstdev_msgs_.clear();
00489   }
00490 
00491   void NovatelGps::GetRangeMessages(std::vector<novatel_gps_msgs::RangePtr>& range_messages)
00492   {
00493     range_messages.resize(range_msgs_.size());
00494     std::copy(range_msgs_.begin(), range_msgs_.end(), range_messages.begin());
00495     range_msgs_.clear();
00496   }
00497 
00498   void NovatelGps::GetTimeMessages(std::vector<novatel_gps_msgs::TimePtr>& time_messages)
00499   {
00500     time_messages.resize(time_msgs_.size());
00501     std::copy(time_msgs_.begin(), time_msgs_.end(), time_messages.begin());
00502     time_msgs_.clear();
00503   }
00504 
00505   void NovatelGps::GetTrackstatMessages(std::vector<novatel_gps_msgs::TrackstatPtr>& trackstat_msgs)
00506   {
00507     trackstat_msgs.resize(trackstat_msgs_.size());
00508     std::copy(trackstat_msgs_.begin(), trackstat_msgs_.end(), trackstat_msgs.begin());
00509     trackstat_msgs_.clear();
00510   }
00511 
00512   bool NovatelGps::CreatePcapConnection(const std::string& device, NovatelMessageOpts const& opts)
00513   {
00514     ROS_INFO("Opening pcap file: %s", device.c_str());
00515 
00516     if ((pcap_ = pcap_open_offline(device.c_str(), pcap_errbuf_)) == NULL)
00517     {
00518       ROS_FATAL("Unable to open pcap file.");
00519       return false;
00520     }
00521 
00522     pcap_compile(pcap_, &pcap_packet_filter_, "tcp dst port 3001", 1, PCAP_NETMASK_UNKNOWN);
00523     is_connected_ = true;
00524 
00525     return true;
00526   }
00527 
00528   bool NovatelGps::CreateSerialConnection(const std::string& device, NovatelMessageOpts const& opts)
00529   {
00530     swri_serial_util::SerialConfig config;
00531     config.baud = 115200;
00532     config.parity = swri_serial_util::SerialConfig::NO_PARITY;
00533     config.flow_control = false;
00534     config.data_bits = 8;
00535     config.stop_bits = 1;
00536     config.low_latency_mode = false;
00537     config.writable = true; // Assume that we can write to this port
00538 
00539     bool success = serial_.Open(device, config);
00540 
00541     if (success)
00542     {
00543       is_connected_ = true;
00544       if (!Configure(opts))
00545       {
00546         // We will not kill the connection here, because the device may already
00547         // be setup to communicate correctly, but we will print a warning         
00548         ROS_ERROR("Failed to configure GPS. This port may be read only, or the "
00549                  "device may not be functioning as expected; however, the "
00550                  "driver may still function correctly if the port has already "
00551                  "been pre-configured.");
00552       }
00553     }
00554     else
00555     {
00556       error_msg_ = serial_.ErrorMsg();
00557     }
00558 
00559     return success;
00560   }
00561 
00562   bool NovatelGps::CreateIpConnection(const std::string& endpoint, NovatelMessageOpts const& opts)
00563   {
00564     std::string ip;
00565     std::string port;
00566     uint16_t num_port;
00567     size_t sep_pos = endpoint.find(':');
00568     if (sep_pos == std::string::npos || sep_pos == endpoint.size() - 1)
00569     {
00570       ROS_INFO("Using default port.");
00571       std::stringstream ss;
00572       if (connection_ == TCP)
00573       {
00574         num_port = DEFAULT_TCP_PORT;
00575       }
00576       else
00577       {
00578         num_port = DEFAULT_UDP_PORT;
00579       }
00580       ss << num_port;
00581       port = ss.str();
00582     }
00583     else
00584     {
00585       port = endpoint.substr(sep_pos + 1);
00586     }
00587 
00588     if (sep_pos != 0)
00589     {
00590       ip = endpoint.substr(0, sep_pos);
00591     }
00592 
00593     try
00594     {
00595       if (!ip.empty())
00596       {
00597         if (connection_ == TCP)
00598         {
00599           boost::asio::ip::tcp::resolver resolver(io_service_);
00600           boost::asio::ip::tcp::resolver::query query(ip, port);
00601           boost::asio::ip::tcp::resolver::iterator iter = resolver.resolve(query);
00602 
00603           boost::asio::connect(tcp_socket_, iter);
00604           ROS_INFO("Connecting via TCP to %s:%s", ip.c_str(), port.c_str());
00605         }
00606         else
00607         {
00608           boost::asio::ip::udp::resolver resolver(io_service_);
00609           boost::asio::ip::udp::resolver::query query(ip, port);
00610           udp_endpoint_ = boost::make_shared<boost::asio::ip::udp::endpoint>(*resolver.resolve(query));
00611           udp_socket_.reset(new boost::asio::ip::udp::socket(io_service_));
00612           udp_socket_->open(boost::asio::ip::udp::v4());
00613           ROS_INFO("Connecting via UDP to %s:%s", ip.c_str(), port.c_str());
00614         }
00615       }
00616       else
00617       {
00618         uint16_t port_num = static_cast<uint16_t>(strtoll(port.c_str(), NULL, 10));
00619         if (connection_ == TCP)
00620         {
00621           boost::asio::ip::tcp::acceptor acceptor(io_service_,
00622                                                   boost::asio::ip::tcp::endpoint(
00623                                                       boost::asio::ip::tcp::v4(), port_num));
00624           ROS_INFO("Listening on TCP port %s", port.c_str());
00625           acceptor.accept(tcp_socket_);
00626           ROS_INFO("Accepted TCP connection from client: %s",
00627                    tcp_socket_.remote_endpoint().address().to_string().c_str());
00628         }
00629         else
00630         {
00631           udp_socket_.reset(new boost::asio::ip::udp::socket(
00632               io_service_,
00633               boost::asio::ip::udp::endpoint(boost::asio::ip::udp::v4(),
00634                                              port_num)));
00635           boost::array<char, 1> recv_buf;
00636           udp_endpoint_ = boost::make_shared<boost::asio::ip::udp::endpoint>();
00637           boost::system::error_code error;
00638 
00639           ROS_INFO("Listening on UDP port %s", port.c_str());
00640           udp_socket_->receive_from(boost::asio::buffer(recv_buf), *udp_endpoint_, 0, error);
00641           if (error && error != boost::asio::error::message_size)
00642           {
00643             throw boost::system::system_error(error);
00644           }
00645 
00646           ROS_INFO("Accepted UDP connection from client: %s",
00647                    udp_endpoint_->address().to_string().c_str());
00648         }
00649       }
00650     }
00651     catch (std::exception& e)
00652     {
00653       error_msg_ = e.what();
00654       ROS_ERROR("Unable to connect: %s", e.what());
00655       return false;
00656     }
00657 
00658     is_connected_ = true;
00659 
00660     if (Configure(opts))
00661     {
00662       ROS_INFO("Configured GPS.");
00663     }
00664     else
00665     {
00666       // We will not kill the connection here, because the device may already
00667       // be setup to communicate correctly, but we will print a warning
00668       ROS_ERROR("Failed to configure GPS. This port may be read only, or the "
00669                    "device may not be functioning as expected; however, the "
00670                    "driver may still function correctly if the port has already "
00671                    "been pre-configured.");
00672     }
00673 
00674     return true;
00675   }
00676 
00677   NovatelGps::ReadResult NovatelGps::ReadData()
00678   {
00679     if (connection_ == SERIAL)
00680     {
00681       swri_serial_util::SerialPort::Result result =
00682           serial_.ReadBytes(data_buffer_, 0, 1000);
00683 
00684       if (result == swri_serial_util::SerialPort::ERROR)
00685       {
00686         error_msg_ = serial_.ErrorMsg();
00687         return READ_ERROR;
00688       }
00689       else if (result == swri_serial_util::SerialPort::TIMEOUT)
00690       {
00691         error_msg_ = "Timed out waiting for serial device.";
00692         return READ_TIMEOUT;
00693       }
00694       else if (result == swri_serial_util::SerialPort::INTERRUPTED)
00695       {
00696         error_msg_ = "Interrupted during read from serial device.";
00697         return READ_INTERRUPTED;
00698       }
00699 
00700       return READ_SUCCESS;
00701     }
00702     else if (connection_ == TCP || connection_ == UDP)
00703     {
00704       try
00705       {
00706         boost::system::error_code error;
00707         size_t len;
00708 
00709         if (connection_ == TCP)
00710         {
00711           len = tcp_socket_.read_some(boost::asio::buffer(socket_buffer_), error);
00712         }
00713         else
00714         {
00715           boost::asio::ip::udp::endpoint remote_endpoint;
00716           len = udp_socket_->receive_from(boost::asio::buffer(socket_buffer_), remote_endpoint);
00717         }
00718         data_buffer_.insert(data_buffer_.end(), socket_buffer_.begin(), socket_buffer_.begin()+len);
00719         if (error)
00720         {
00721           error_msg_ = error.message();
00722           Disconnect();
00723           return READ_ERROR;
00724         }
00725         return READ_SUCCESS;
00726       }
00727       catch (std::exception& e)
00728       {
00729         ROS_WARN("TCP connection error: %s", e.what());
00730       }
00731     }
00732     else if (connection_ == PCAP)
00733     {
00734       struct pcap_pkthdr* header;
00735       const u_char *pkt_data;
00736 
00737       int result;
00738       result = pcap_next_ex(pcap_, &header, &pkt_data);
00739       if (result >= 0)
00740       {
00741         struct iphdr* iph = (struct iphdr*)(pkt_data + sizeof(struct ethhdr));
00742         uint32_t iphdrlen = iph->ihl * 4;
00743 
00744         switch (iph->protocol)
00745         {
00746           case 6: // TCP
00747           {
00748             if (header->len == 54)
00749             {
00750               // Empty packet, skip it.
00751               return READ_SUCCESS;
00752             }
00753 
00754             // It's possible to get multiple subsequent TCP packets with the same seq
00755             // but latter ones have more data than previous ones.  In case that happens,
00756             // we need to only process the one with the most data.  We do that by
00757             // storing the most recently received message in a buffer, replacing it if
00758             // we get a new one with the same seq but more data, and only sending it to
00759             // the parser when we get a new packet with a different seq.
00760             // Note that when we copy data into last_tcp_packet_, we omit the ethernet
00761             // header because we don't care about it; we still need the IP and TCP
00762             // headers.  After we move it from last_tcp_packet_ into data_buffer, we
00763             // can skip the IP header and the TCP data offset.
00764             bool store_packet = true;
00765             if (!last_tcp_packet_.empty())
00766             {
00767               struct tcphdr* tcph = (struct tcphdr*) (pkt_data + iphdrlen + sizeof(struct ethhdr));
00768               struct iphdr* last_iph = (struct iphdr*) (&(last_tcp_packet_[0]));
00769               uint32_t last_iphdrlen = last_iph->ihl * 4;
00770               struct tcphdr* last_tcph = (struct tcphdr*) (&(last_tcp_packet_[0]) + last_iphdrlen);
00771               uint16_t last_len = ntohs(static_cast<uint16_t>(last_iph->tot_len));
00772               uint16_t new_len = ntohs(static_cast<uint16_t>(iph->tot_len));
00773               uint32_t last_seq = ntohl(last_tcph->seq);
00774               uint32_t new_seq = ntohl(tcph->seq);
00775 
00776               if (new_seq != last_seq)
00777               {
00778                 // If we got a packet that has a different seq than our previous one, send
00779                 // the previous one and store the new one.
00780                 uint32_t data_offset = last_tcph->doff * 4;
00781                 data_buffer_.insert(data_buffer_.end(),
00782                                     last_tcp_packet_.begin() + last_iphdrlen + data_offset,
00783                                     last_tcp_packet_.end());
00784               }
00785               else if (new_len <= last_len)
00786               {
00787                 // If we got a packet with the same seq as the previous one but it doesn't
00788                 // have more data, do nothing.
00789                 store_packet = false;
00790               }
00791             }
00792 
00793             if (store_packet)
00794             {
00795               // If we get here, we either just sent the previous packet, or we got
00796               // a new packet with the same seq but more data.  In either case,
00797               // store it.
00798               last_tcp_packet_.clear();
00799               last_tcp_packet_.insert(last_tcp_packet_.end(),
00800                                       pkt_data + sizeof(struct ethhdr),
00801                                       pkt_data + header->len);
00802             }
00803 
00804             break;
00805           }
00806           case 17: // UDP
00807           {
00808             uint16_t frag_off = ntohs(static_cast<uint16_t>(iph->frag_off));
00809             uint16_t fragment_offset = frag_off & static_cast<uint16_t>(0x1FFF);
00810             size_t header_size;
00811             // UDP packets may be fragmented; this isn't really "correct", but for
00812             // simplicity's sake we'll assume we get fragments in the right order.
00813             if (fragment_offset == 0)
00814             {
00815               header_size = sizeof(struct ethhdr) + iphdrlen + sizeof(struct udphdr);
00816             }
00817             else
00818             {
00819               header_size = sizeof(struct ethhdr) + iphdrlen;
00820             }
00821 
00822             data_buffer_.insert(data_buffer_.end(), pkt_data + header_size, pkt_data + header->len);
00823 
00824             break;
00825           }
00826           default:
00827             ROS_WARN("Unexpected protocol: %u", iph->protocol);
00828             return READ_ERROR;
00829         }
00830 
00831         // Add a slight delay after reading packets; if the node is being tested offline
00832         // and this loop is hammering the TCP, logs won't output properly.
00833         ros::Duration(0.001).sleep();
00834 
00835         return READ_SUCCESS;
00836       }
00837       else if (result == -2)
00838       {
00839         ROS_INFO("Done reading pcap file.");
00840         if (!last_tcp_packet_.empty())
00841         {
00842           // Don't forget to submit the last packet if we still have one!
00843           struct iphdr* last_iph = (struct iphdr*) (&(last_tcp_packet_[0]));
00844           uint32_t iphdrlen = last_iph->ihl * 4;
00845           struct tcphdr* last_tcph = (struct tcphdr*) (&(last_tcp_packet_[0]) + iphdrlen);
00846           uint32_t data_offset = last_tcph->doff * 4;
00847           data_buffer_.insert(data_buffer_.end(),
00848                               last_tcp_packet_.begin() + iphdrlen + data_offset,
00849                               last_tcp_packet_.end());
00850           last_tcp_packet_.clear();
00851         }
00852         Disconnect();
00853         return READ_SUCCESS;
00854       }
00855       else
00856       {
00857         ROS_WARN("Error reading pcap data: %s", pcap_geterr(pcap_));
00858         return READ_ERROR;
00859       }
00860     }
00861 
00862     error_msg_ = "Unsupported connection type.";
00863 
00864     return READ_ERROR;
00865   }
00866 
00867   void NovatelGps::GetImuMessages(std::vector<sensor_msgs::ImuPtr>& imu_messages)
00868   {
00869     imu_messages.clear();
00870     imu_messages.insert(imu_messages.end(), imu_msgs_.begin(), imu_msgs_.end());
00871     imu_msgs_.clear();
00872   }
00873 
00874   void NovatelGps::GenerateImuMessages()
00875   {
00876     if (imu_rate_ <= 0.0)
00877     {
00878       ROS_WARN_ONCE("IMU rate has not been configured; cannot produce sensor_msgs/Imu messages.");
00879       return;
00880     }
00881 
00882     if (!latest_insstdev_ && !latest_inscov_)
00883     {
00884       // If we haven't received an INSSTDEV or an INSCOV message, don't do anything, just return.
00885       ROS_WARN_THROTTLE(1.0, "No INSSTDEV or INSCOV data yet; orientation covariance will be unavailable.");
00886     }
00887 
00888     size_t previous_size = imu_msgs_.size();
00889     // Only do anything if we have both CORRIMUDATA and INSPVA messages.
00890     while (!corrimudata_queue_.empty() && !inspva_queue_.empty())
00891     {
00892       novatel_gps_msgs::NovatelCorrectedImuDataPtr corrimudata = corrimudata_queue_.front();
00893       novatel_gps_msgs::InspvaPtr inspva = inspva_queue_.front();
00894 
00895       double corrimudata_time = corrimudata->gps_week_num * SECONDS_PER_WEEK + corrimudata->gps_seconds;
00896       double inspva_time = inspva->novatel_msg_header.gps_week_num *
00897                                SECONDS_PER_WEEK + inspva->novatel_msg_header.gps_seconds;
00898 
00899       if (std::fabs(corrimudata_time - inspva_time) > IMU_TOLERANCE_S)
00900       {
00901         // If the two messages are too far apart to sync, discard the oldest one.
00902         ROS_DEBUG("INSPVA and CORRIMUDATA were unacceptably far apart.");
00903         if (corrimudata_time < inspva_time)
00904         {
00905           ROS_DEBUG("Discarding oldest CORRIMUDATA.");
00906           corrimudata_queue_.pop();
00907           continue;
00908         }
00909         else
00910         {
00911           ROS_DEBUG("Discarding oldest INSPVA.");
00912           inspva_queue_.pop();
00913           continue;
00914         }
00915       }
00916       // If we've successfully matched up two messages, remove them from their queues.
00917       inspva_queue_.pop();
00918       corrimudata_queue_.pop();
00919 
00920       // Now we can combine them together to make an Imu message.
00921       sensor_msgs::ImuPtr imu = boost::make_shared<sensor_msgs::Imu>();
00922 
00923       imu->header.stamp = corrimudata->header.stamp;
00924       imu->orientation = tf::createQuaternionMsgFromRollPitchYaw(inspva->roll * DEGREES_TO_RADIANS,
00925                                               -(inspva->pitch) * DEGREES_TO_RADIANS,
00926                                               -(inspva->azimuth) * DEGREES_TO_RADIANS);
00927 
00928       if (latest_inscov_)
00929       {
00930         imu->orientation_covariance = latest_inscov_->attitude_covariance;
00931       }
00932       else if (latest_insstdev_)
00933       {
00934         imu->orientation_covariance[0] = std::pow(2, latest_insstdev_->pitch_dev);
00935         imu->orientation_covariance[4] = std::pow(2, latest_insstdev_->roll_dev);
00936         imu->orientation_covariance[8] = std::pow(2, latest_insstdev_->azimuth_dev);
00937       }
00938       else
00939       {
00940         imu->orientation_covariance[0] =
00941         imu->orientation_covariance[4] =
00942         imu->orientation_covariance[8] = 1e-3;
00943       }
00944 
00945       imu->angular_velocity.x = corrimudata->pitch_rate * imu_rate_;
00946       imu->angular_velocity.y = corrimudata->roll_rate * imu_rate_;
00947       imu->angular_velocity.z = corrimudata->yaw_rate * imu_rate_;
00948       imu->angular_velocity_covariance[0] =
00949       imu->angular_velocity_covariance[4] =
00950       imu->angular_velocity_covariance[8] = 1e-3;
00951 
00952       imu->linear_acceleration.x = corrimudata->lateral_acceleration * imu_rate_;
00953       imu->linear_acceleration.y = corrimudata->longitudinal_acceleration * imu_rate_;
00954       imu->linear_acceleration.z = corrimudata->vertical_acceleration * imu_rate_;
00955       imu->linear_acceleration_covariance[0] =
00956       imu->linear_acceleration_covariance[4] =
00957       imu->linear_acceleration_covariance[8] = 1e-3;
00958 
00959       imu_msgs_.push_back(imu);
00960     }
00961 
00962     size_t new_size = imu_msgs_.size() - previous_size;
00963     ROS_DEBUG("Created %lu new sensor_msgs/Imu messages.", new_size);
00964   }
00965 
00966   void NovatelGps::SetImuRate(double imu_rate)
00967   {
00968     ROS_INFO("IMU sample rate: %f", imu_rate);
00969     imu_rate_ = imu_rate;
00970   }
00971 
00972   NovatelGps::ReadResult NovatelGps::ParseBinaryMessage(const BinaryMessage& msg,
00973                                                         const ros::Time& stamp) throw(ParseException)
00974   {
00975     switch (msg.header_.message_id_)
00976     {
00977       case BestposParser::MESSAGE_ID:
00978       {
00979         novatel_gps_msgs::NovatelPositionPtr position = bestpos_parser_.ParseBinary(msg);
00980         position->header.stamp = stamp;
00981         novatel_positions_.push_back(position);
00982         position_sync_buffer_.push_back(position);
00983         break;
00984       }
00985       case BestvelParser::MESSAGE_ID:
00986       {
00987         novatel_gps_msgs::NovatelVelocityPtr velocity = bestvel_parser_.ParseBinary(msg);
00988         velocity->header.stamp = stamp;
00989         novatel_velocities_.push_back(velocity);
00990         break;
00991       }
00992       case CorrImuDataParser::MESSAGE_ID:
00993       {
00994         novatel_gps_msgs::NovatelCorrectedImuDataPtr imu = corrimudata_parser_.ParseBinary(msg);
00995         imu->header.stamp = stamp;
00996         corrimudata_msgs_.push_back(imu);
00997         corrimudata_queue_.push(imu);
00998         if (corrimudata_queue_.size() > MAX_BUFFER_SIZE)
00999         {
01000           ROS_WARN_THROTTLE(1.0, "CORRIMUDATA queue overflow.");
01001           corrimudata_queue_.pop();
01002         }
01003         GenerateImuMessages();
01004         break;
01005       }
01006       case InscovParser::MESSAGE_ID:
01007       {
01008         novatel_gps_msgs::InscovPtr inscov = inscov_parser_.ParseBinary(msg);
01009         inscov->header.stamp = stamp;
01010         inscov_msgs_.push_back(inscov);
01011         latest_inscov_ = inscov;
01012         break;
01013       }
01014       case InspvaParser::MESSAGE_ID:
01015       {
01016         novatel_gps_msgs::InspvaPtr inspva = inspva_parser_.ParseBinary(msg);
01017         inspva->header.stamp = stamp;
01018         inspva_msgs_.push_back(inspva);
01019         inspva_queue_.push(inspva);
01020         if (inspva_queue_.size() > MAX_BUFFER_SIZE)
01021         {
01022           ROS_WARN_THROTTLE(1.0, "INSPVA queue overflow.");
01023           inspva_queue_.pop();
01024         }
01025         GenerateImuMessages();
01026         break;
01027       }
01028       case InsstdevParser::MESSAGE_ID:
01029       {
01030         novatel_gps_msgs::InsstdevPtr insstdev = insstdev_parser_.ParseBinary(msg);
01031         insstdev->header.stamp = stamp;
01032         insstdev_msgs_.push_back(insstdev);
01033         latest_insstdev_ = insstdev;
01034         break;
01035       }
01036       case RangeParser::MESSAGE_ID:
01037       {
01038         novatel_gps_msgs::RangePtr range = range_parser_.ParseBinary(msg);
01039         range->header.stamp = stamp;
01040         range_msgs_.push_back(range);
01041         break;
01042       }
01043       case TimeParser::MESSAGE_ID:
01044       {
01045         novatel_gps_msgs::TimePtr time = time_parser_.ParseBinary(msg);
01046         utc_offset_ = time->utc_offset;
01047         ROS_DEBUG("Got a new TIME with offset %f. UTC offset is %f", time->utc_offset, utc_offset_);
01048         time->header.stamp = stamp;
01049         time_msgs_.push_back(time);
01050         break;
01051       }
01052       case TrackstatParser::MESSAGE_ID:
01053       {
01054         novatel_gps_msgs::TrackstatPtr trackstat = trackstat_parser_.ParseBinary(msg);
01055         trackstat->header.stamp = stamp;
01056         trackstat_msgs_.push_back(trackstat);
01057         break;
01058       }
01059       default:
01060         ROS_WARN("Unexpected binary message id: %u", msg.header_.message_id_);
01061         break;
01062     }
01063 
01064     return READ_SUCCESS;
01065   }
01066 
01067   NovatelGps::ReadResult NovatelGps::ParseNmeaSentence(const NmeaSentence& sentence,
01068                                                        const ros::Time& stamp,
01069                                                        double most_recent_utc_time) throw(ParseException)
01070   {
01071     if (sentence.id == GpggaParser::MESSAGE_NAME)
01072     {
01073       novatel_gps_msgs::GpggaPtr gpgga = gpgga_parser_.ParseAscii(sentence);
01074 
01075       if (most_recent_utc_time < gpgga->utc_seconds)
01076       {
01077         most_recent_utc_time = gpgga->utc_seconds;
01078       }
01079 
01080       gpgga->header.stamp = stamp - ros::Duration(most_recent_utc_time - gpgga->utc_seconds);
01081 
01082       if (gpgga_parser_.WasLastGpsValid())
01083       {
01084         gpgga_msgs_.push_back(gpgga);
01085 
01086         // Make a deep copy for the sync buffer so the GPSFix messages
01087         // don't get adjusted multiple times for the sync offset.
01088         gpgga_sync_buffer_.push_back(*gpgga);
01089       }
01090       else
01091       {
01092         gpgga_msgs_.push_back(gpgga);
01093       }
01094     }
01095     else if (sentence.id == GprmcParser::MESSAGE_NAME)
01096     {
01097       novatel_gps_msgs::GprmcPtr gprmc = gprmc_parser_.ParseAscii(sentence);
01098 
01099       if (most_recent_utc_time < gprmc->utc_seconds)
01100       {
01101         most_recent_utc_time = gprmc->utc_seconds;
01102       }
01103 
01104       gprmc->header.stamp = stamp - ros::Duration(most_recent_utc_time - gprmc->utc_seconds);
01105 
01106       if (gprmc_parser_.WasLastGpsValid())
01107       {
01108         gprmc_msgs_.push_back(gprmc);
01109 
01110         // Make a deep copy for the sync buffer so the GPSFix messages
01111         // don't get adjusted multiple times for the sync offset.
01112         gprmc_sync_buffer_.push_back(*gprmc);
01113       }
01114       else
01115       {
01116         gprmc_msgs_.push_back(gprmc);
01117       }
01118     }
01119     else if (sentence.id == GpgsaParser::MESSAGE_NAME)
01120     {
01121       novatel_gps_msgs::GpgsaPtr gpgsa = gpgsa_parser_.ParseAscii(sentence);
01122       gpgsa_msgs_.push_back(gpgsa);
01123     }
01124     else if (sentence.id == GpgsvParser::MESSAGE_NAME)
01125     {
01126       novatel_gps_msgs::GpgsvPtr gpgsv = gpgsv_parser_.ParseAscii(sentence);
01127       gpgsv_msgs_.push_back(gpgsv);
01128     }
01129     else
01130     {
01131       ROS_DEBUG_STREAM("Unrecognized NMEA sentence " << sentence.id);
01132     }
01133 
01134     return READ_SUCCESS;
01135   }
01136 
01137   NovatelGps::ReadResult NovatelGps::ParseNovatelSentence(const NovatelSentence& sentence,
01138                                                           const ros::Time& stamp) throw(ParseException)
01139   {
01140     if (sentence.id == "BESTPOSA")
01141     {
01142       novatel_gps_msgs::NovatelPositionPtr position = bestpos_parser_.ParseAscii(sentence);
01143       position->header.stamp = stamp;
01144       novatel_positions_.push_back(position);
01145       position_sync_buffer_.push_back(position);
01146     }
01147     else if (sentence.id == "BESTVELA")
01148     {
01149       novatel_gps_msgs::NovatelVelocityPtr velocity = bestvel_parser_.ParseAscii(sentence);
01150       velocity->header.stamp = stamp;
01151       novatel_velocities_.push_back(velocity);
01152     }
01153     else if (sentence.id == "CORRIMUDATAA")
01154     {
01155       novatel_gps_msgs::NovatelCorrectedImuDataPtr imu = corrimudata_parser_.ParseAscii(sentence);
01156       imu->header.stamp = stamp;
01157       corrimudata_msgs_.push_back(imu);
01158       corrimudata_queue_.push(imu);
01159       if (corrimudata_queue_.size() > MAX_BUFFER_SIZE)
01160       {
01161         ROS_WARN_THROTTLE(1.0, "CORRIMUDATA queue overflow.");
01162         corrimudata_queue_.pop();
01163       }
01164       GenerateImuMessages();
01165     }
01166     else if (sentence.id == "INSCOVA")
01167     {
01168       novatel_gps_msgs::InscovPtr inscov = inscov_parser_.ParseAscii(sentence);
01169       inscov->header.stamp = stamp;
01170       inscov_msgs_.push_back(inscov);
01171       latest_inscov_ = inscov;
01172     }
01173     else if (sentence.id == "INSPVAA")
01174     {
01175       novatel_gps_msgs::InspvaPtr inspva = inspva_parser_.ParseAscii(sentence);
01176       inspva->header.stamp = stamp;
01177       inspva_msgs_.push_back(inspva);
01178       inspva_queue_.push(inspva);
01179       if (inspva_queue_.size() > MAX_BUFFER_SIZE)
01180       {
01181         ROS_WARN_THROTTLE(1.0, "INSPVA queue overflow.");
01182         inspva_queue_.pop();
01183       }
01184       GenerateImuMessages();
01185     }
01186     else if (sentence.id == "INSSTDEVA")
01187     {
01188       novatel_gps_msgs::InsstdevPtr insstdev = insstdev_parser_.ParseAscii(sentence);
01189       insstdev->header.stamp = stamp;
01190       insstdev_msgs_.push_back(insstdev);
01191       latest_insstdev_ = insstdev;
01192     }
01193     else if (sentence.id == "TIMEA")
01194     {
01195       novatel_gps_msgs::TimePtr time = time_parser_.ParseAscii(sentence);
01196       utc_offset_ = time->utc_offset;
01197       ROS_DEBUG("Got a new TIME with offset %f. UTC offset is %f", time->utc_offset, utc_offset_);
01198       time->header.stamp = stamp;
01199       time_msgs_.push_back(time);
01200     }
01201     else if (sentence.id == "RANGEA")
01202     {
01203       novatel_gps_msgs::RangePtr range = range_parser_.ParseAscii(sentence);
01204       range->header.stamp = stamp;
01205       range_msgs_.push_back(range);
01206     }
01207     else if (sentence.id == "TRACKSTATA")
01208     {
01209       novatel_gps_msgs::TrackstatPtr trackstat = trackstat_parser_.ParseAscii(sentence);
01210       trackstat->header.stamp = stamp;
01211       trackstat_msgs_.push_back(trackstat);
01212     }
01213 
01214     return READ_SUCCESS;
01215   }
01216 
01217   bool NovatelGps::Write(const std::string& command)
01218   {
01219     std::vector<uint8_t> bytes(command.begin(), command.end());
01220 
01221     if (connection_ == SERIAL)
01222     {
01223       int32_t written = serial_.Write(bytes);
01224       if (written != (int32_t)command.length())
01225       {
01226         ROS_ERROR("Failed to send command: %s", command.c_str());
01227       }
01228       return written == (int32_t)command.length();
01229     }
01230     else if (connection_ == TCP || connection_ == UDP)
01231     {
01232       boost::system::error_code error;
01233       try
01234       {
01235         size_t written;
01236         if (connection_ == TCP)
01237         {
01238           written = boost::asio::write(tcp_socket_, boost::asio::buffer(bytes), error);
01239         }
01240         else
01241         {
01242           written = udp_socket_->send_to(boost::asio::buffer(bytes), *udp_endpoint_, 0, error);
01243         }
01244         if (error)
01245         {
01246           ROS_ERROR("Error writing TCP data: %s", error.message().c_str());
01247           Disconnect();
01248         }
01249         ROS_DEBUG("Wrote %lu bytes.", written);
01250         return written == (int32_t) command.length();
01251       }
01252       catch (std::exception& e)
01253       {
01254         Disconnect();
01255         ROS_ERROR("Exception writing TCP data: %s", e.what());
01256       }
01257     }
01258     else if (connection_ == PCAP)
01259     {
01260       ROS_WARN_ONCE("Writing data is unsupported in pcap mode.");
01261       return true;
01262     }
01263 
01264     return false;
01265   }
01266 
01267   bool NovatelGps::Configure(NovatelMessageOpts const& opts)
01268   {
01269     bool configured = true;
01270     configured = configured && Write("unlogall\n");
01271     for(NovatelMessageOpts::const_iterator option = opts.begin(); option != opts.end(); ++option)
01272     {
01273       std::stringstream command;
01274       command << std::setprecision(3);
01275       command << "log " << option->first << " ontime " << option->second << "\n";
01276       configured = configured && Write(command.str());
01277     }
01278     return configured;
01279   }
01280 }


novatel_gps_driver
Author(s):
autogenerated on Sun Oct 8 2017 02:40:29