node.cpp
Go to the documentation of this file.
00001 //==============================================================================
00002 // Copyright (c) 2012, Johannes Meyer, TU Darmstadt
00003 // All rights reserved.
00004 
00005 // Redistribution and use in source and binary forms, with or without
00006 // modification, are permitted provided that the following conditions are met:
00007 //     * Redistributions of source code must retain the above copyright
00008 //       notice, this list of conditions and the following disclaimer.
00009 //     * Redistributions in binary form must reproduce the above copyright
00010 //       notice, this list of conditions and the following disclaimer in the
00011 //       documentation and/or other materials provided with the distribution.
00012 //     * Neither the name of the Flight Systems and Automatic Control group,
00013 //       TU Darmstadt, nor the names of its contributors may be used to
00014 //       endorse or promote products derived from this software without
00015 //       specific prior written permission.
00016 
00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018 // AND
00019 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00020 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00021 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
00022 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00023 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00024 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00025 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00026 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00027 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00028 //==============================================================================
00029 
00030 #include "ublox_gps/node.h"
00031 
00032 using namespace ublox_node;
00033 
00034 //
00035 // ublox_node namespace
00036 //
00037 uint8_t ublox_node::modelFromString(const std::string& model) {
00038   std::string lower = model;
00039   std::transform(lower.begin(), lower.end(), lower.begin(), ::tolower);
00040   if(lower == "portable") {
00041     return ublox_msgs::CfgNAV5::DYN_MODEL_PORTABLE;
00042   } else if(lower == "stationary") {
00043     return ublox_msgs::CfgNAV5::DYN_MODEL_STATIONARY;
00044   } else if(lower == "pedestrian") {
00045     return ublox_msgs::CfgNAV5::DYN_MODEL_PEDESTRIAN;
00046   } else if(lower == "automotive") {
00047     return ublox_msgs::CfgNAV5::DYN_MODEL_AUTOMOTIVE;
00048   } else if(lower == "sea") {
00049     return ublox_msgs::CfgNAV5::DYN_MODEL_SEA;
00050   } else if(lower == "airborne1") {
00051     return ublox_msgs::CfgNAV5::DYN_MODEL_AIRBORNE_1G;
00052   } else if(lower == "airborne2") {
00053     return ublox_msgs::CfgNAV5::DYN_MODEL_AIRBORNE_2G;
00054   } else if(lower == "airborne4") {
00055     return ublox_msgs::CfgNAV5::DYN_MODEL_AIRBORNE_4G;
00056   } else if(lower == "wristwatch") {
00057     return ublox_msgs::CfgNAV5::DYN_MODEL_WRIST_WATCH;
00058   }
00059 
00060   throw std::runtime_error("Invalid settings: " + lower + 
00061                            " is not a valid dynamic model.");
00062 }
00063 
00064 uint8_t ublox_node::fixModeFromString(const std::string& mode) {
00065   std::string lower = mode;
00066   std::transform(lower.begin(), lower.end(), lower.begin(), ::tolower);
00067   if (lower == "2d") {
00068     return ublox_msgs::CfgNAV5::FIX_MODE_2D_ONLY;
00069   } else if (lower == "3d") {
00070     return ublox_msgs::CfgNAV5::FIX_MODE_3D_ONLY;
00071   } else if (lower == "auto") {
00072     return ublox_msgs::CfgNAV5::FIX_MODE_AUTO;
00073   }
00074 
00075   throw std::runtime_error("Invalid settings: " + mode + 
00076                            " is not a valid fix mode.");
00077 }
00078 
00079 //
00080 // u-blox ROS Node
00081 //
00082 UbloxNode::UbloxNode() {
00083   initialize();
00084 }
00085 
00086 void UbloxNode::addFirmwareInterface() {
00087   int ublox_version;
00088   if (protocol_version_ < 14) {
00089     components_.push_back(ComponentPtr(new UbloxFirmware6));
00090     ublox_version = 6;
00091   } else if (protocol_version_ >= 14 && protocol_version_ <= 15) {
00092     components_.push_back(ComponentPtr(new UbloxFirmware7));
00093     ublox_version = 7;
00094   } else {
00095     components_.push_back(ComponentPtr(new UbloxFirmware8));
00096     ublox_version = 8;
00097   }
00098   ROS_INFO("U-Blox Firmware Version: %d", ublox_version);
00099 }
00100 
00101 
00102 void UbloxNode::addProductInterface(std::string product_category, 
00103                                     std::string ref_rov) {
00104   if (product_category.compare("HPG") == 0 && ref_rov.compare("REF") == 0)
00105     components_.push_back(ComponentPtr(new HpgRefProduct));
00106   else if (product_category.compare("HPG") == 0 && ref_rov.compare("ROV") == 0)
00107     components_.push_back(ComponentPtr(new HpgRovProduct));
00108   else if (product_category.compare("TIM") == 0)
00109     components_.push_back(ComponentPtr(new TimProduct));
00110   else if (product_category.compare("ADR") == 0 || 
00111            product_category.compare("UDR") == 0)
00112     components_.push_back(ComponentPtr(new AdrUdrProduct));
00113   else if (product_category.compare("FTS") == 0)
00114     components_.push_back(ComponentPtr(new FtsProduct));
00115   else if(product_category.compare("SPG") != 0)
00116     ROS_WARN("Product category %s %s from MonVER message not recognized %s", 
00117              product_category.c_str(), ref_rov.c_str(),
00118              "options are HPG REF, HPG ROV, TIM, ADR, UDR, FTS, SPG");
00119 }
00120 
00121 void UbloxNode::getRosParams() {
00122   nh->param("device", device_, std::string("/dev/ttyACM0"));
00123   nh->param("frame_id", frame_id, std::string("gps"));
00124   
00125   // Save configuration parameters
00126   getRosUint("load/mask", load_.loadMask, 0);
00127   getRosUint("load/device", load_.deviceMask, 0);
00128   getRosUint("save/mask", save_.saveMask, 0);
00129   getRosUint("save/device", save_.deviceMask, 0);
00130 
00131   // UART 1 params
00132   getRosUint("uart1/baudrate", baudrate_, 9600);
00133   getRosUint("uart1/in", uart_in_, ublox_msgs::CfgPRT::PROTO_UBX 
00134                                     | ublox_msgs::CfgPRT::PROTO_NMEA
00135                                     | ublox_msgs::CfgPRT::PROTO_RTCM);
00136   getRosUint("uart1/out", uart_out_, ublox_msgs::CfgPRT::PROTO_UBX);
00137   // USB params
00138   if (nh->hasParam("usb/in") || nh->hasParam("usb/out")) {
00139     set_usb_ = true;
00140     if(!getRosUint("usb/in", usb_in_)) {
00141       throw std::runtime_error(std::string("usb/out is set, therefore ") + 
00142         "usb/in must be set");
00143     }
00144     if(!getRosUint("usb/out", usb_out_)) {
00145       throw std::runtime_error(std::string("usb/in is set, therefore ") + 
00146         "usb/out must be set");
00147     }
00148     getRosUint("usb/tx_ready", usb_tx_, 0);
00149   }
00150   // Measurement rate params
00151   nh->param("rate", rate_, 4.0);  // in Hz
00152   getRosUint("nav_rate", nav_rate, 1);  // # of measurement rate cycles
00153   // RTCM params
00154   getRosUint("rtcm/ids", rtcm_ids);  // RTCM output message IDs 
00155   getRosUint("rtcm/rates", rtcm_rates);  // RTCM output message rates
00156   // PPP: Advanced Setting
00157   nh->param("enable_ppp", enable_ppp_, false);
00158   // SBAS params, only for some devices
00159   nh->param("sbas", enable_sbas_, false);
00160   getRosUint("sbas/max", max_sbas_, 0); // Maximum number of SBAS channels
00161   getRosUint("sbas/usage", sbas_usage_, 0);
00162   nh->param("dynamic_model", dynamic_model_, std::string("portable"));
00163   nh->param("fix_mode", fix_mode_, std::string("auto"));
00164   getRosUint("dr_limit", dr_limit_, 0); // Dead reckoning limit
00165 
00166   if (enable_ppp_) 
00167     ROS_WARN("Warning: PPP is enabled - this is an expert setting.");
00168 
00169   checkMin(rate_, 0, "rate");
00170 
00171   if(rtcm_ids.size() != rtcm_rates.size())
00172     throw std::runtime_error(std::string("Invalid settings: size of rtcm_ids") +
00173                              " must match size of rtcm_rates");
00174     
00175   dmodel_ = modelFromString(dynamic_model_);
00176   fmode_ = fixModeFromString(fix_mode_);
00177 
00178   nh->param("dat/set", set_dat_, false);
00179   if(set_dat_) {
00180     std::vector<float> shift, rot;
00181     if (!nh->getParam("dat/majA", cfg_dat_.majA)
00182         || nh->getParam("dat/flat", cfg_dat_.flat)
00183         || nh->getParam("dat/shift", shift)
00184         || nh->getParam("dat/rot", rot)
00185         || nh->getParam("dat/scale", cfg_dat_.scale))
00186       throw std::runtime_error(std::string("dat/set is true, therefore ") +
00187          "dat/majA, dat/flat, dat/shift, dat/rot, & dat/scale must be set");
00188     if(shift.size() != 3 || rot.size() != 3)
00189       throw std::runtime_error(std::string("size of dat/shift & dat/rot ") +
00190                                "must be 3");
00191     checkRange(cfg_dat_.majA, 6300000.0, 6500000.0, "dat/majA");
00192     checkRange(cfg_dat_.flat, 0.0, 500.0, "dat/flat");
00193     
00194     checkRange(shift, 0.0, 500.0, "dat/shift");
00195     cfg_dat_.dX = shift[0];
00196     cfg_dat_.dY = shift[1];
00197     cfg_dat_.dZ = shift[2];
00198 
00199     checkRange(rot, -5000.0, 5000.0, "dat/rot");
00200     cfg_dat_.rotX = rot[0];
00201     cfg_dat_.rotY = rot[1];
00202     cfg_dat_.rotZ = rot[2];
00203     
00204     checkRange(cfg_dat_.scale, 0.0, 50.0, "scale");
00205   }
00206   
00207   // measurement period [ms]
00208   meas_rate = 1000 / rate_;
00209 }
00210 
00211 void UbloxNode::pollMessages(const ros::TimerEvent& event) {
00212   static std::vector<uint8_t> payload(1, 1);
00213   if (enabled["aid_alm"])
00214     gps.poll(ublox_msgs::Class::AID, ublox_msgs::Message::AID::ALM, payload);
00215   if (enabled["aid_eph"])
00216     gps.poll(ublox_msgs::Class::AID, ublox_msgs::Message::AID::EPH, payload);
00217   if (enabled["aid_hui"])
00218     gps.poll(ublox_msgs::Class::AID, ublox_msgs::Message::AID::HUI);
00219  
00220   payload[0]++;
00221   if (payload[0] > 32) {
00222     payload[0] = 1;
00223   }
00224 }
00225 
00226 void UbloxNode::printInf(const ublox_msgs::Inf &m, uint8_t id) {
00227   if (id == ublox_msgs::Message::INF::ERROR)
00228     ROS_ERROR("INF: %s", m.str.data());
00229   else if (id == ublox_msgs::Message::INF::WARNING)
00230     ROS_WARN("INF: %s", m.str.data());
00231   else if (id == ublox_msgs::Message::INF::DEBUG)
00232     ROS_DEBUG("INF: %s", m.str.data());
00233   else
00234     ROS_INFO("INF: %s", m.str.data());
00235 }
00236 
00237 void UbloxNode::subscribe() {
00238   ROS_DEBUG("Subscribing to U-Blox messages");
00239   // subscribe messages
00240   nh->param("publish/all", enabled["all"], false);
00241   nh->param("inf/all", enabled["inf"], true);
00242   nh->param("publish/nav/all", enabled["nav"], enabled["all"]);
00243   nh->param("publish/rxm/all", enabled["rxm"], enabled["all"]);
00244   nh->param("publish/aid/all", enabled["aid"], enabled["all"]);
00245   nh->param("publish/mon/all", enabled["mon"], enabled["all"]);
00246   
00247   // Nav Messages
00248   nh->param("publish/nav/status", enabled["nav_status"], enabled["nav"]);
00249   if (enabled["nav_status"])
00250     gps.subscribe<ublox_msgs::NavSTATUS>(boost::bind(
00251         publish<ublox_msgs::NavSTATUS>, _1, "navstatus"), kSubscribeRate);
00252   
00253   nh->param("publish/nav/posecef", enabled["nav_posecef"], enabled["nav"]);
00254   if (enabled["nav_posecef"])
00255     gps.subscribe<ublox_msgs::NavPOSECEF>(boost::bind(
00256         publish<ublox_msgs::NavPOSECEF>, _1, "navposecef"), kSubscribeRate);
00257 
00258   nh->param("publish/nav/clock", enabled["nav_clock"], enabled["nav"]);
00259   if (enabled["nav_clock"])
00260     gps.subscribe<ublox_msgs::NavCLOCK>(boost::bind(
00261         publish<ublox_msgs::NavCLOCK>, _1, "navclock"), kSubscribeRate);  
00262   
00263   // INF messages
00264   nh->param("inf/debug", enabled["inf_debug"], false);
00265   if (enabled["inf_debug"])
00266     gps.subscribeId<ublox_msgs::Inf>(
00267         boost::bind(&UbloxNode::printInf, this, _1, 
00268                     ublox_msgs::Message::INF::DEBUG), 
00269         ublox_msgs::Message::INF::DEBUG);
00270 
00271   nh->param("inf/error", enabled["inf_error"], enabled["inf"]);
00272   if (enabled["inf_error"])
00273     gps.subscribeId<ublox_msgs::Inf>(
00274         boost::bind(&UbloxNode::printInf, this, _1, 
00275                     ublox_msgs::Message::INF::ERROR), 
00276         ublox_msgs::Message::INF::ERROR);
00277 
00278   nh->param("inf/notice", enabled["inf_notice"], enabled["inf"]);
00279   if (enabled["inf_notice"])
00280     gps.subscribeId<ublox_msgs::Inf>(
00281         boost::bind(&UbloxNode::printInf, this, _1, 
00282                     ublox_msgs::Message::INF::NOTICE), 
00283         ublox_msgs::Message::INF::NOTICE);
00284 
00285   nh->param("inf/test", enabled["inf_test"], enabled["inf"]);
00286   if (enabled["inf_test"])
00287     gps.subscribeId<ublox_msgs::Inf>(
00288         boost::bind(&UbloxNode::printInf, this, _1, 
00289                     ublox_msgs::Message::INF::TEST), 
00290         ublox_msgs::Message::INF::TEST);
00291 
00292   nh->param("inf/warning", enabled["inf_warning"], enabled["inf"]);
00293   if (enabled["inf_warning"])
00294     gps.subscribeId<ublox_msgs::Inf>(
00295         boost::bind(&UbloxNode::printInf, this, _1, 
00296                     ublox_msgs::Message::INF::WARNING), 
00297         ublox_msgs::Message::INF::WARNING);
00298 
00299   // AID messages
00300   nh->param("publish/aid/alm", enabled["aid_alm"], enabled["aid"]);
00301   if (enabled["aid_alm"]) 
00302     gps.subscribe<ublox_msgs::AidALM>(boost::bind(
00303         publish<ublox_msgs::AidALM>, _1, "aidalm"), kSubscribeRate);
00304   
00305   nh->param("publish/aid/eph", enabled["aid_eph"], enabled["aid"]);
00306   if (enabled["aid_eph"]) 
00307     gps.subscribe<ublox_msgs::AidEPH>(boost::bind(
00308         publish<ublox_msgs::AidEPH>, _1, "aideph"), kSubscribeRate);
00309   
00310   nh->param("publish/aid/hui", enabled["aid_hui"], enabled["aid"]);
00311   if (enabled["aid_hui"]) 
00312     gps.subscribe<ublox_msgs::AidHUI>(boost::bind(
00313         publish<ublox_msgs::AidHUI>, _1, "aidhui"), kSubscribeRate);
00314 
00315   for(int i = 0; i < components_.size(); i++)
00316     components_[i]->subscribe();
00317 }
00318 
00319 void UbloxNode::initializeRosDiagnostics() {
00320   if (!nh->hasParam("diagnostic_period"))
00321     nh->setParam("diagnostic_period", kDiagnosticPeriod);
00322   
00323   updater.reset(new diagnostic_updater::Updater());
00324   updater->setHardwareID("ublox");
00325 
00326   // configure diagnostic updater for frequency
00327   freq_diag = FixDiagnostic(std::string("fix"), kFixFreqTol, 
00328                             kFixFreqWindow, kTimeStampStatusMin);
00329   for(int i = 0; i < components_.size(); i++)
00330     components_[i]->initializeRosDiagnostics();
00331 }
00332 
00333 
00334 void UbloxNode::processMonVer() {
00335   ublox_msgs::MonVER monVer;
00336   if (!gps.poll(monVer))
00337     throw std::runtime_error("Failed to poll MonVER & set relevant settings");
00338 
00339   ROS_DEBUG("%s, HW VER: %s", monVer.swVersion.c_array(), 
00340                monVer.hwVersion.c_array());
00341   // Convert extension to vector of strings
00342   std::vector<std::string> extension;
00343   extension.reserve(monVer.extension.size());
00344   for(std::size_t i = 0; i < monVer.extension.size(); ++i) {
00345     ROS_DEBUG("%s", monVer.extension[i].field.c_array());
00346     // Find the end of the string (null character)
00347     unsigned char* end = std::find(monVer.extension[i].field.begin(), 
00348           monVer.extension[i].field.end(), '\0');
00349     extension.push_back(std::string(monVer.extension[i].field.begin(), end));
00350   }
00351 
00352   // Get the protocol version
00353   for(std::size_t i = 0; i < extension.size(); ++i) {
00354     std::size_t found = extension[i].find("PROTVER");
00355     if (found != std::string::npos) {
00356       protocol_version_ = ::atof(
00357           extension[i].substr(8, extension[i].size()-8).c_str());
00358       break;
00359     }
00360   }
00361   if (protocol_version_ == 0)
00362     ROS_WARN("Failed to parse MonVER and determine protocol version. %s",
00363              "Defaulting to firmware version 6.");
00364   addFirmwareInterface();
00365 
00366   if(protocol_version_ < 18) {
00367     // Final line contains supported GNSS delimited by ;
00368     std::vector<std::string> strs;
00369     boost::split(strs, extension[extension.size()-1], boost::is_any_of(";"));
00370     for(size_t i = 0; i < strs.size(); i++)
00371       supported.insert(strs[i]);
00372   } else {
00373     for(std::size_t i = 0; i < extension.size(); ++i) {
00374       std::vector<std::string> strs;
00375       // Up to 2nd to last line
00376       if(i <= extension.size() - 2) {
00377         boost::split(strs, extension[i], boost::is_any_of("="));
00378         if(strs.size() > 1) {
00379           if (strs[0].compare(std::string("FWVER")) == 0) {
00380             if(strs[1].length() > 8)
00381               addProductInterface(strs[1].substr(0, 3), strs[1].substr(8, 10));
00382             else
00383               addProductInterface(strs[1].substr(0, 3));
00384             continue;
00385           }
00386         }
00387       }
00388       // Last 1-2 lines contain supported GNSS
00389       if(i >= extension.size() - 2) {
00390         boost::split(strs, extension[i], boost::is_any_of(";"));
00391         for(size_t i = 0; i < strs.size(); i++)
00392           supported.insert(strs[i]);
00393       }
00394     }
00395   }
00396 }
00397 
00398 bool UbloxNode::configureUblox() {
00399   try {
00400     if (!gps.isInitialized())
00401       throw std::runtime_error("Failed to initialize.");
00402     if (load_.loadMask != 0) {
00403       ROS_DEBUG("Loading u-blox configuration from memory. %u", load_.loadMask);
00404       if (!gps.configure(load_))
00405         throw std::runtime_error(std::string("Failed to load configuration ") +
00406                                  "from memory");
00407       if (load_.loadMask & load_.MASK_IO_PORT) {
00408         ROS_DEBUG("Loaded I/O configuration from memory, resetting serial %s", 
00409           "communications.");
00410         boost::posix_time::seconds wait(kResetWait);
00411         gps.reset(wait);
00412         if (!gps.isConfigured())
00413           throw std::runtime_error(std::string("Failed to reset serial I/O") +
00414             "after loading I/O configurations from device memory.");
00415       }
00416     }
00417 
00418     if (set_usb_) {
00419       gps.configUsb(usb_tx_, usb_in_, usb_out_);
00420     }
00421     if (!gps.configRate(meas_rate, nav_rate)) {
00422       std::stringstream ss;
00423       ss << "Failed to set measurement rate to " << meas_rate 
00424          << "ms and navigation rate to " << nav_rate;
00425       throw std::runtime_error(ss.str());
00426     }
00427     // If device doesn't have SBAS, will receive NACK (causes exception)
00428     if(supportsGnss("SBAS")) {
00429       if (!gps.configSbas(enable_sbas_, sbas_usage_, max_sbas_)) {
00430         throw std::runtime_error(std::string("Failed to ") +
00431                                  ((enable_sbas_) ? "enable" : "disable") +
00432                                  " SBAS.");
00433       }
00434     }
00435     if (!gps.setPpp(enable_ppp_))
00436       throw std::runtime_error(std::string("Failed to ") +
00437                                ((enable_ppp_) ? "enable" : "disable") 
00438                                + " PPP.");
00439     if (!gps.setDynamicModel(dmodel_))
00440       throw std::runtime_error("Failed to set model: " + dynamic_model_ + ".");
00441     if (!gps.setFixMode(fmode_))
00442       throw std::runtime_error("Failed to set fix mode: " + fix_mode_ + ".");
00443     if (!gps.setDeadReckonLimit(dr_limit_)) {
00444       std::stringstream ss;
00445       ss << "Failed to set dead reckoning limit: " << dr_limit_ << ".";
00446       throw std::runtime_error(ss.str());
00447     }
00448     if (set_dat_ && !gps.configure(cfg_dat_))
00449       throw std::runtime_error("Failed to set user-defined datum.");
00450     // Configure each component
00451     for (int i = 0; i < components_.size(); i++) {
00452       if(!components_[i]->configureUblox())
00453         return false;
00454     }
00455     if (save_.saveMask != 0) {
00456       ROS_DEBUG("Saving the u-blox configuration, mask %u, device %u",
00457                 save_.saveMask, save_.deviceMask);
00458       if(!gps.configure(save_))
00459         ROS_ERROR("u-blox unable to save configuration to non-volatile memory");
00460     }
00461   } catch (std::exception& e) {
00462     ROS_FATAL("Error configuring u-blox: %s", e.what());
00463     return false;
00464   }
00465   return true;
00466 }
00467 
00468 void UbloxNode::configureInf() {
00469   ublox_msgs::CfgINF msg;
00470   // Subscribe to UBX INF messages
00471   ublox_msgs::CfgINF_Block block;
00472   block.protocolID = block.PROTOCOL_ID_UBX;
00473   // Enable desired INF messages on each UBX port
00474   uint8_t mask = (enabled["inf_error"] ? block.INF_MSG_ERROR : 0) |
00475                  (enabled["inf_warning"] ? block.INF_MSG_WARNING : 0) |
00476                  (enabled["inf_notice"] ? block.INF_MSG_NOTICE : 0) |
00477                  (enabled["inf_test"] ? block.INF_MSG_TEST : 0) |
00478                  (enabled["inf_debug"] ? block.INF_MSG_DEBUG : 0);
00479   for (int i = 0; i < block.infMsgMask.size(); i++)
00480     block.infMsgMask[i] = mask;
00481 
00482   msg.blocks.push_back(block);
00483 
00484   // IF NMEA is enabled
00485   if (uart_in_ & ublox_msgs::CfgPRT::PROTO_NMEA) {
00486     ublox_msgs::CfgINF_Block block;
00487     block.protocolID = block.PROTOCOL_ID_NMEA;
00488     // Enable desired INF messages on each NMEA port
00489     for (int i = 0; i < block.infMsgMask.size(); i++)
00490       block.infMsgMask[i] = mask;
00491     msg.blocks.push_back(block);
00492   }
00493 
00494   ROS_DEBUG("Configuring INF messages");
00495   if (!gps.configure(msg))
00496     ROS_WARN("Failed to configure INF messages");
00497 }
00498 
00499 void UbloxNode::initializeIo() {
00500   boost::smatch match;
00501   if (boost::regex_match(device_, match,
00502                          boost::regex("(tcp|udp)://(.+):(\\d+)"))) {
00503     std::string proto(match[1]);
00504     if (proto == "tcp") {
00505       std::string host(match[2]);
00506       std::string port(match[3]);
00507       ROS_INFO("Connecting to %s://%s:%s ...", proto.c_str(), host.c_str(),
00508                port.c_str());
00509       gps.initializeTcp(host, port);
00510     } else {
00511       throw std::runtime_error("Protocol '" + proto + "' is unsupported");
00512     }
00513   } else {
00514     gps.initializeSerial(device_, baudrate_, uart_in_, uart_out_);
00515   }
00516 }
00517 
00518 void UbloxNode::initialize() {
00519   // Params must be set before initializing IO
00520   getRosParams();
00521   initializeIo();
00522   // Must process Mon VER before setting firmware/hardware params
00523   processMonVer();
00524   if(protocol_version_ <= 14) {
00525     if(nh->param("raw_data", false))
00526       components_.push_back(ComponentPtr(new RawDataProduct));
00527   }
00528   // Must set firmware & hardware params before initializing diagnostics
00529   for (int i = 0; i < components_.size(); i++)
00530     components_[i]->getRosParams();
00531   // Do this last
00532   initializeRosDiagnostics();    
00533 
00534   if (configureUblox()) {
00535     ROS_INFO("U-Blox configured successfully.");
00536     // Subscribe to all U-Blox messages
00537     subscribe();
00538     // Configure INF messages (needs INF params, call after subscribing)
00539     configureInf();
00540 
00541     ros::Timer poller; 
00542     poller = nh->createTimer(ros::Duration(kPollDuration), 
00543                              &UbloxNode::pollMessages, 
00544                              this);
00545     poller.start();
00546     ros::spin();
00547   }
00548   shutdown();
00549 }
00550 
00551 void UbloxNode::shutdown() {
00552   if (gps.isInitialized()) {
00553     gps.close();
00554     ROS_INFO("Closed connection to %s.", device_.c_str());
00555   }
00556 }
00557 
00558 //
00559 // U-Blox Firmware (all versions) 
00560 //
00561 void UbloxFirmware::initializeRosDiagnostics() {
00562   updater->add("fix", this, &UbloxFirmware::fixDiagnostic);
00563   updater->force_update();
00564 }
00565 
00566 //
00567 // U-Blox Firmware Version 6
00568 //
00569 UbloxFirmware6::UbloxFirmware6() {}
00570 
00571 void UbloxFirmware6::getRosParams() {
00572   // Fix Service type, used when publishing fix status messages
00573   fix_status_service = sensor_msgs::NavSatStatus::SERVICE_GPS;  
00574   
00575   nh->param("nmea/set", set_nmea_, false);
00576   if (set_nmea_) {
00577     bool compat, consider;
00578 
00579     if (!getRosUint("nmea/version", cfg_nmea_.version))
00580       throw std::runtime_error(std::string("Invalid settings: nmea/set is ") +
00581           "true, therefore nmea/version must be set");
00582     if (!getRosUint("nmea/num_sv", cfg_nmea_.numSV))
00583       throw std::runtime_error(std::string("Invalid settings: nmea/set is ") +
00584                 "true, therefore nmea/num_sv must be set");
00585     if (!nh->getParam("nmea/compat", compat))
00586         throw std::runtime_error(std::string("Invalid settings: nmea/set is ") +
00587           "true, therefore nmea/compat must be set");
00588     if (!nh->getParam("nmea/consider", consider))
00589       throw std::runtime_error(std::string("Invalid settings: nmea/set is ") +
00590           "true, therefore nmea/consider must be set");
00591 
00592     // set flags
00593     cfg_nmea_.flags = compat ? cfg_nmea_.FLAGS_COMPAT : 0;
00594     cfg_nmea_.flags |= consider ? cfg_nmea_.FLAGS_CONSIDER : 0;
00595 
00596     // set filter
00597     bool temp;
00598     nh->param("nmea/filter/pos", temp, false);
00599     cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_POS : 0;
00600     nh->param("nmea/filter/msk_pos", temp, false);
00601     cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_MSK_POS : 0;
00602     nh->param("nmea/filter/time", temp, false);
00603     cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_TIME : 0;
00604     nh->param("nmea/filter/date", temp, false);
00605     cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_DATE : 0;
00606     nh->param("nmea/filter/sbas", temp, false);
00607     cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_SBAS_FILT : 0;
00608     nh->param("nmea/filter/track", temp, false);
00609     cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_TRACK : 0;
00610   }  
00611 }
00612 
00613 bool UbloxFirmware6::configureUblox() {  
00614   ROS_WARN("ublox_version < 7, ignoring GNSS settings");
00615 
00616   if (set_nmea_ && !gps.configure(cfg_nmea_))
00617     throw std::runtime_error("Failed to configure NMEA");
00618 
00619   return true;
00620 }
00621 
00622 void UbloxFirmware6::subscribe() {
00623   // Whether or not to publish Nav POS LLH (always subscribes)
00624   nh->param("publish/nav/posllh", enabled["nav_posllh"], enabled["nav"]);
00625   nh->param("publish/nav/sol", enabled["nav_sol"], enabled["nav"]);
00626   nh->param("publish/nav/velned", enabled["nav_velned"], enabled["nav"]);
00627   
00628   // Always subscribes to these messages, but may not publish to ROS topic
00629   // Subscribe to Nav POSLLH
00630   gps.subscribe<ublox_msgs::NavPOSLLH>(boost::bind(
00631       &UbloxFirmware6::callbackNavPosLlh, this, _1), kSubscribeRate);
00632   gps.subscribe<ublox_msgs::NavSOL>(boost::bind(
00633   // Subscribe to Nav SOL
00634       &UbloxFirmware6::callbackNavSol, this, _1), kSubscribeRate);
00635   // Subscribe to Nav VELNED
00636   gps.subscribe<ublox_msgs::NavVELNED>(boost::bind(
00637       &UbloxFirmware6::callbackNavVelNed, this, _1), kSubscribeRate);
00638   
00639   // Subscribe to Nav SVINFO
00640   nh->param("publish/nav/svinfo", enabled["nav_svinfo"], enabled["nav"]);
00641   if (enabled["nav_svinfo"])
00642     gps.subscribe<ublox_msgs::NavSVINFO>(boost::bind(
00643         publish<ublox_msgs::NavSVINFO>, _1, "navsvinfo"), 
00644         kNavSvInfoSubscribeRate);
00645 
00646   // Subscribe to Mon HW
00647   nh->param("publish/mon_hw", enabled["mon_hw"], enabled["mon"]);
00648   if (enabled["mon_hw"])
00649     gps.subscribe<ublox_msgs::MonHW6>(boost::bind(
00650         publish<ublox_msgs::MonHW6>, _1, "monhw"), kSubscribeRate);
00651 }
00652 
00653 void UbloxFirmware6::fixDiagnostic(
00654     diagnostic_updater::DiagnosticStatusWrapper& stat) {
00655   // Set the diagnostic level based on the fix status
00656   if (last_nav_sol_.gpsFix == ublox_msgs::NavSOL::GPS_DEAD_RECKONING_ONLY) {
00657     stat.level = diagnostic_msgs::DiagnosticStatus::WARN;
00658     stat.message = "Dead reckoning only";
00659   } else if (last_nav_sol_.gpsFix == ublox_msgs::NavSOL::GPS_2D_FIX) {
00660     stat.level = diagnostic_msgs::DiagnosticStatus::OK;
00661     stat.message = "2D fix";
00662   } else if (last_nav_sol_.gpsFix == ublox_msgs::NavSOL::GPS_3D_FIX) {
00663     stat.level = diagnostic_msgs::DiagnosticStatus::OK;
00664     stat.message = "3D fix";
00665   } else if (last_nav_sol_.gpsFix ==
00666              ublox_msgs::NavSOL::GPS_GPS_DEAD_RECKONING_COMBINED) {
00667     stat.level = diagnostic_msgs::DiagnosticStatus::OK;
00668     stat.message = "GPS and dead reckoning combined";
00669   } else if (last_nav_sol_.gpsFix == ublox_msgs::NavSOL::GPS_TIME_ONLY_FIX) {
00670     stat.level = diagnostic_msgs::DiagnosticStatus::OK;
00671     stat.message = "Time fix only";
00672   } 
00673   // If fix is not ok (within DOP & Accuracy Masks), raise the diagnostic level
00674   if (!(last_nav_sol_.flags & ublox_msgs::NavSOL::FLAGS_GPS_FIX_OK)) {
00675     stat.level = diagnostic_msgs::DiagnosticStatus::WARN;
00676     stat.message += ", fix not ok";
00677   } 
00678   // Raise diagnostic level to error if no fix
00679   if (last_nav_sol_.gpsFix == ublox_msgs::NavSOL::GPS_NO_FIX) {
00680     stat.level = diagnostic_msgs::DiagnosticStatus::ERROR;
00681     stat.message = "No fix";
00682   }
00683 
00684   // Add last fix position
00685   stat.add("iTOW [ms]", last_nav_pos_.iTOW);
00686   stat.add("Latitude [deg]", last_nav_pos_.lat * 1e-7);
00687   stat.add("Longitude [deg]", last_nav_pos_.lon * 1e-7);
00688   stat.add("Altitude [m]", last_nav_pos_.height * 1e-3);
00689   stat.add("Height above MSL [m]", last_nav_pos_.hMSL * 1e-3);
00690   stat.add("Horizontal Accuracy [m]", last_nav_pos_.hAcc * 1e-3);
00691   stat.add("Vertical Accuracy [m]", last_nav_pos_.vAcc * 1e-3);
00692   stat.add("# SVs used", (int)last_nav_sol_.numSV);
00693 }
00694 
00695 void UbloxFirmware6::callbackNavPosLlh(const ublox_msgs::NavPOSLLH& m) {
00696   if(enabled["nav_posllh"]) {
00697     static ros::Publisher publisher =
00698         nh->advertise<ublox_msgs::NavPOSLLH>("navposllh", kROSQueueSize);
00699     publisher.publish(m);
00700   }
00701 
00702   // Position message
00703   static ros::Publisher fixPublisher =
00704       nh->advertise<sensor_msgs::NavSatFix>("fix", kROSQueueSize);
00705   if (m.iTOW == last_nav_vel_.iTOW)
00706     fix_.header.stamp = velocity_.header.stamp; // use last timestamp
00707   else
00708     fix_.header.stamp = ros::Time::now(); // new timestamp
00709   
00710   fix_.header.frame_id = frame_id;
00711   fix_.latitude = m.lat * 1e-7;
00712   fix_.longitude = m.lon * 1e-7;
00713   fix_.altitude = m.height * 1e-3;
00714   
00715   if (last_nav_sol_.gpsFix >= last_nav_sol_.GPS_2D_FIX)
00716     fix_.status.status = fix_.status.STATUS_FIX;
00717   else
00718     fix_.status.status = fix_.status.STATUS_NO_FIX;
00719 
00720   // Convert from mm to m
00721   const double varH = pow(m.hAcc / 1000.0, 2);
00722   const double varV = pow(m.vAcc / 1000.0, 2);
00723 
00724   fix_.position_covariance[0] = varH;
00725   fix_.position_covariance[4] = varH;
00726   fix_.position_covariance[8] = varV;
00727   fix_.position_covariance_type =
00728       sensor_msgs::NavSatFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
00729 
00730   fix_.status.service = fix_.status.SERVICE_GPS;
00731   fixPublisher.publish(fix_);
00732   last_nav_pos_ = m;
00733   //  update diagnostics
00734   freq_diag.diagnostic->tick(fix_.header.stamp);
00735   updater->update();
00736 }
00737 
00738 void UbloxFirmware6::callbackNavVelNed(const ublox_msgs::NavVELNED& m) {
00739   if(enabled["nav_velned"]) {
00740     static ros::Publisher publisher =
00741         nh->advertise<ublox_msgs::NavVELNED>("navvelned", kROSQueueSize);
00742     publisher.publish(m);
00743   }
00744 
00745   // Example geometry message
00746   static ros::Publisher velocityPublisher =
00747       nh->advertise<geometry_msgs::TwistWithCovarianceStamped>("fix_velocity",
00748                                                                 kROSQueueSize);
00749   if (m.iTOW == last_nav_pos_.iTOW)
00750     velocity_.header.stamp = fix_.header.stamp; // same time as last navposllh
00751   else
00752     velocity_.header.stamp = ros::Time::now(); // create a new timestamp
00753   velocity_.header.frame_id = frame_id;
00754 
00755   //  convert to XYZ linear velocity
00756   velocity_.twist.twist.linear.x = m.velE / 100.0;
00757   velocity_.twist.twist.linear.y = m.velN / 100.0;
00758   velocity_.twist.twist.linear.z = -m.velD / 100.0;
00759 
00760   const double varSpeed = pow(m.sAcc / 100.0, 2);
00761 
00762   const int cols = 6;
00763   velocity_.twist.covariance[cols * 0 + 0] = varSpeed;
00764   velocity_.twist.covariance[cols * 1 + 1] = varSpeed;
00765   velocity_.twist.covariance[cols * 2 + 2] = varSpeed;
00766   velocity_.twist.covariance[cols * 3 + 3] = -1;  //  angular rate unsupported
00767 
00768   velocityPublisher.publish(velocity_);
00769   last_nav_vel_ = m;
00770 }
00771 
00772 void UbloxFirmware6::callbackNavSol(const ublox_msgs::NavSOL& m) {
00773   if(enabled["nav_sol"]) {
00774     static ros::Publisher publisher =
00775         nh->advertise<ublox_msgs::NavSOL>("navsol", kROSQueueSize);
00776     publisher.publish(m);
00777   }
00778   last_nav_sol_ = m;
00779 }
00780 
00781 //
00782 // Ublox Firmware Version 7
00783 //
00784 UbloxFirmware7::UbloxFirmware7() {}
00785 
00786 void UbloxFirmware7::getRosParams() {
00787   //
00788   // GNSS configuration
00789   //
00790   // GNSS enable/disable
00791   nh->param("gnss/gps", enable_gps_, true);
00792   nh->param("gnss/glonass", enable_glonass_, false);
00793   nh->param("gnss/qzss", enable_qzss_, false);
00794   getRosUint("gnss/qzss_sig_cfg", qzss_sig_cfg_, 
00795               ublox_msgs::CfgGNSS_Block::SIG_CFG_QZSS_L1CA);
00796   nh->param("gnss/sbas", enable_sbas_, false);
00797   
00798   if(enable_gps_ && !supportsGnss("GPS")) 
00799     ROS_WARN("gnss/gps is true, but GPS GNSS is not supported by this device");
00800   if(enable_glonass_ && !supportsGnss("GLO")) 
00801     ROS_WARN("gnss/glonass is true, but GLONASS is not %s", 
00802              "supported by this device");
00803   if(enable_qzss_ && !supportsGnss("QZSS")) 
00804     ROS_WARN("gnss/qzss is true, but QZSS is not supported by this device");
00805   if(enable_sbas_ && !supportsGnss("SBAS")) 
00806     ROS_WARN("gnss/sbas is true, but SBAS is not supported by this device");
00807   
00808   if(nh->hasParam("gnss/galileo")) 
00809     ROS_WARN("ublox_version < 8, ignoring Galileo GNSS Settings");
00810   if(nh->hasParam("gnss/beidou")) 
00811     ROS_WARN("ublox_version < 8, ignoring BeiDou Settings");
00812   if(nh->hasParam("gnss/imes")) 
00813     ROS_WARN("ublox_version < 8, ignoring IMES GNSS Settings");
00814 
00815   // Fix Service type, used when publishing fix status messages
00816   fix_status_service = sensor_msgs::NavSatStatus::SERVICE_GPS 
00817       + (enable_glonass_ ? 1 : 0) * sensor_msgs::NavSatStatus::SERVICE_GLONASS;
00818 
00819   //
00820   // NMEA Configuration
00821   //
00822   nh->param("nmea/set", set_nmea_, false);
00823   if (set_nmea_) {
00824     bool compat, consider;
00825 
00826     if (!getRosUint("nmea/version", cfg_nmea_.nmeaVersion))
00827       throw std::runtime_error(std::string("Invalid settings: nmea/set is ") +
00828           "true, therefore nmea/version must be set");
00829     if (!getRosUint("nmea/num_sv", cfg_nmea_.numSV))
00830       throw std::runtime_error(std::string("Invalid settings: nmea/set is ") +
00831                 "true, therefore nmea/num_sv must be set");
00832     if (!getRosUint("nmea/sv_numbering", cfg_nmea_.svNumbering))
00833       throw std::runtime_error(std::string("Invalid settings: nmea/set is ") +
00834           "true, therefore nmea/sv_numbering must be set");
00835     if (!nh->getParam("nmea/compat", compat))
00836         throw std::runtime_error(std::string("Invalid settings: nmea/set is ") +
00837           "true, therefore nmea/compat must be set");
00838     if (!nh->getParam("nmea/consider", consider))
00839       throw std::runtime_error(std::string("Invalid settings: nmea/set is ") +
00840           "true, therefore nmea/consider must be set");
00841 
00842     // set flags
00843     cfg_nmea_.flags = compat ? cfg_nmea_.FLAGS_COMPAT : 0;
00844     cfg_nmea_.flags |= consider ? cfg_nmea_.FLAGS_CONSIDER : 0;
00845     // set filter
00846     bool temp;
00847     nh->param("nmea/filter/pos", temp, false);
00848     cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_POS : 0;
00849     nh->param("nmea/filter/msk_pos", temp, false);
00850     cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_MSK_POS : 0;
00851     nh->param("nmea/filter/time", temp, false);
00852     cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_TIME : 0;
00853     nh->param("nmea/filter/date", temp, false);
00854     cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_DATE : 0;
00855     nh->param("nmea/filter/gps_only", temp, false);
00856     cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_GPS_ONLY : 0;
00857     nh->param("nmea/filter/track", temp, false);
00858     cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_TRACK : 0;
00859     // set gnssToFilter
00860     nh->param("nmea/gnssToFilter/gps", temp, false);
00861     cfg_nmea_.gnssToFilter |= temp ? cfg_nmea_.GNSS_TO_FILTER_GPS : 0;
00862     nh->param("nmea/gnssToFilter/sbas", temp, false);
00863     cfg_nmea_.gnssToFilter |= temp ? cfg_nmea_.GNSS_TO_FILTER_SBAS : 0;
00864     nh->param("nmea/gnssToFilter/qzss", temp, false);
00865     cfg_nmea_.gnssToFilter |= temp ? cfg_nmea_.GNSS_TO_FILTER_QZSS : 0;
00866     nh->param("nmea/gnssToFilter/glonass", temp, false);
00867     cfg_nmea_.gnssToFilter |= temp ? cfg_nmea_.GNSS_TO_FILTER_GLONASS : 0;
00868 
00869     getRosUint("nmea/main_talker_id", cfg_nmea_.mainTalkerId);
00870     getRosUint("nmea/gsv_talker_id", cfg_nmea_.gsvTalkerId);
00871   } 
00872 }
00873 
00874 bool UbloxFirmware7::configureUblox() {
00876   ublox_msgs::CfgGNSS cfgGNSSRead;
00877   if (gps.poll(cfgGNSSRead)) {
00878     ROS_DEBUG("Read GNSS config.");
00879     ROS_DEBUG("Num. tracking channels in hardware: %i", cfgGNSSRead.numTrkChHw);
00880     ROS_DEBUG("Num. tracking channels to use: %i", cfgGNSSRead.numTrkChUse);
00881   } else {
00882     throw std::runtime_error("Failed to read the GNSS config.");
00883   }
00884 
00885   ublox_msgs::CfgGNSS cfgGNSSWrite;
00886   cfgGNSSWrite.numConfigBlocks = 1;  // do services one by one
00887   cfgGNSSWrite.numTrkChHw = cfgGNSSRead.numTrkChHw;
00888   cfgGNSSWrite.numTrkChUse = cfgGNSSRead.numTrkChUse;
00889   cfgGNSSWrite.msgVer = 0;
00890   
00891   // configure GLONASS
00892   if(supportsGnss("GLO")) {
00893     ublox_msgs::CfgGNSS_Block block;
00894     block.gnssId = block.GNSS_ID_GLONASS;
00895     block.resTrkCh = block.RES_TRK_CH_GLONASS;
00896     block.maxTrkCh = block.MAX_TRK_CH_GLONASS;
00897     block.flags = enable_glonass_ ? block.SIG_CFG_GLONASS_L1OF : 0;
00898     cfgGNSSWrite.blocks.push_back(block);
00899     if (!gps.configure(cfgGNSSWrite)) {
00900       throw std::runtime_error(std::string("Failed to ") +
00901                                ((enable_glonass_) ? "enable" : "disable") +
00902                                " GLONASS.");
00903     }
00904   }
00905   
00906   if(supportsGnss("QZSS")) {
00907     // configure QZSS
00908     ublox_msgs::CfgGNSS_Block block;
00909     block.gnssId = block.GNSS_ID_QZSS;
00910     block.resTrkCh = block.RES_TRK_CH_QZSS;
00911     block.maxTrkCh = block.MAX_TRK_CH_QZSS;
00912     block.flags = enable_qzss_ ? qzss_sig_cfg_ : 0; 
00913     cfgGNSSWrite.blocks[0] = block;
00914     if (!gps.configure(cfgGNSSWrite)) {
00915       throw std::runtime_error(std::string("Failed to ") +
00916                                ((enable_glonass_) ? "enable" : "disable") +
00917                                " QZSS.");
00918     }
00919   }
00920 
00921   if(supportsGnss("SBAS")) {
00922     // configure SBAS
00923     ublox_msgs::CfgGNSS_Block block;
00924     block.gnssId = block.GNSS_ID_SBAS;
00925     block.resTrkCh = block.RES_TRK_CH_SBAS;
00926     block.maxTrkCh = block.MAX_TRK_CH_SBAS;
00927     block.flags = enable_sbas_ ? block.SIG_CFG_SBAS_L1CA : 0;
00928     cfgGNSSWrite.blocks[0] = block;
00929     if (!gps.configure(cfgGNSSWrite)) {
00930       throw std::runtime_error(std::string("Failed to ") +
00931                                ((enable_sbas_) ? "enable" : "disable") +
00932                                " SBAS.");
00933     }
00934   }
00935 
00936   if(set_nmea_ && !gps.configure(cfg_nmea_))
00937     throw std::runtime_error("Failed to configure NMEA");
00938 
00939   return true;
00940 }
00941 
00942 void UbloxFirmware7::subscribe() {
00943   // Whether to publish Nav PVT messages to a ROS topic
00944   nh->param("publish/nav/pvt", enabled["nav_pvt"], enabled["nav"]);
00945   // Subscribe to Nav PVT (always does so since fix information is published 
00946   // from this)
00947   gps.subscribe<ublox_msgs::NavPVT7>(boost::bind(
00948         &UbloxFirmware7Plus::callbackNavPvt, this, _1),
00949         kSubscribeRate);
00950 
00951   // Subscribe to Nav SVINFO
00952   nh->param("publish/nav/svinfo", enabled["nav_svinfo"], enabled["nav"]);
00953   if (enabled["nav_svinfo"])
00954     gps.subscribe<ublox_msgs::NavSVINFO>(boost::bind(
00955         publish<ublox_msgs::NavSVINFO>, _1, "navsvinfo"), 
00956         kNavSvInfoSubscribeRate);
00957 
00958   // Subscribe to Mon HW
00959   nh->param("publish/mon_hw", enabled["mon_hw"], enabled["mon"]);
00960   if (enabled["mon_hw"])
00961     gps.subscribe<ublox_msgs::MonHW>(boost::bind(
00962         publish<ublox_msgs::MonHW>, _1, "monhw"), kSubscribeRate);
00963 }
00964 
00965 //
00966 // Ublox Version 8 
00967 //
00968 UbloxFirmware8::UbloxFirmware8() {}
00969 
00970 void UbloxFirmware8::getRosParams() {
00971   // UPD SOS configuration
00972   nh->param("clear_bbr", clear_bbr_, false);
00973   gps.setSaveOnShutdown(nh->param("save_on_shutdown", false));
00974 
00975   // GNSS enable/disable
00976   nh->param("gnss/gps", enable_gps_, true);
00977   nh->param("gnss/galileo", enable_galileo_, false);
00978   nh->param("gnss/beidou", enable_beidou_, false);
00979   nh->param("gnss/imes", enable_imes_, false);
00980   nh->param("gnss/glonass", enable_glonass_, false);
00981   nh->param("gnss/qzss", enable_qzss_, false);
00982   nh->param("gnss/sbas", enable_sbas_, false);
00983   // QZSS Signal Configuration
00984   getRosUint("gnss/qzss_sig_cfg", qzss_sig_cfg_, 
00985               ublox_msgs::CfgGNSS_Block::SIG_CFG_QZSS_L1CA);
00986 
00987   if (enable_gps_ && !supportsGnss("GPS")) 
00988     ROS_WARN("gnss/gps is true, but GPS GNSS is not supported by %s",
00989              "this device");
00990   if (enable_glonass_ && !supportsGnss("GLO")) 
00991     ROS_WARN("gnss/glonass is true, but GLONASS is not supported by %s",
00992              "this device");
00993   if (enable_galileo_ && !supportsGnss("GAL")) 
00994     ROS_WARN("gnss/galileo is true, but Galileo GNSS is not supported %s",
00995              "by this device");
00996   if (enable_beidou_ && !supportsGnss("BDS")) 
00997     ROS_WARN("gnss/beidou is true, but Beidou GNSS is not supported %s",
00998              "by this device");
00999   if (enable_imes_ && !supportsGnss("IMES")) 
01000     ROS_WARN("gnss/imes is true, but IMES GNSS is not supported by %s",
01001              "this device");
01002   if (enable_qzss_ && !supportsGnss("QZSS")) 
01003     ROS_WARN("gnss/qzss is true, but QZSS is not supported by this device");
01004   if (enable_sbas_ && !supportsGnss("SBAS")) 
01005     ROS_WARN("gnss/sbas is true, but SBAS is not supported by this device");
01006 
01007   // Fix Service type, used when publishing fix status messages
01008   fix_status_service = sensor_msgs::NavSatStatus::SERVICE_GPS 
01009       + (enable_glonass_ ? 1 : 0) * sensor_msgs::NavSatStatus::SERVICE_GLONASS
01010       + (enable_beidou_ ? 1 : 0) * sensor_msgs::NavSatStatus::SERVICE_COMPASS
01011       + (enable_galileo_ ? 1 : 0) * sensor_msgs::NavSatStatus::SERVICE_GALILEO;
01012 
01013   //
01014   // NMEA Configuration
01015   //
01016   nh->param("nmea/set", set_nmea_, false);
01017   if (set_nmea_) {
01018     bool compat, consider;
01019     cfg_nmea_.version = cfg_nmea_.VERSION; // message version
01020 
01021     // Verify that parameters are set
01022     if (!getRosUint("nmea/version", cfg_nmea_.nmeaVersion))
01023       throw std::runtime_error(std::string("Invalid settings: nmea/set is ") +
01024           "true, therefore nmea/version must be set");
01025     if (!getRosUint("nmea/num_sv", cfg_nmea_.numSV))
01026       throw std::runtime_error(std::string("Invalid settings: nmea/set is ") +
01027                 "true, therefore nmea/num_sv must be set");
01028     if (!getRosUint("nmea/sv_numbering", cfg_nmea_.svNumbering))
01029       throw std::runtime_error(std::string("Invalid settings: nmea/set is ") +
01030           "true, therefore nmea/sv_numbering must be set");
01031     if (!nh->getParam("nmea/compat", compat))
01032         throw std::runtime_error(std::string("Invalid settings: nmea/set is ") +
01033           "true, therefore nmea/compat must be set");
01034     if (!nh->getParam("nmea/consider", consider))
01035       throw std::runtime_error(std::string("Invalid settings: nmea/set is ") +
01036           "true, therefore nmea/consider must be set");
01037 
01038     // set flags
01039     cfg_nmea_.flags = compat ? cfg_nmea_.FLAGS_COMPAT : 0;
01040     cfg_nmea_.flags |= consider ? cfg_nmea_.FLAGS_CONSIDER : 0;
01041     bool temp;
01042     nh->param("nmea/limit82", temp, false);
01043     cfg_nmea_.flags |= temp ? cfg_nmea_.FLAGS_LIMIT82 : 0;
01044     nh->param("nmea/high_prec", temp, false);
01045     cfg_nmea_.flags |= temp ? cfg_nmea_.FLAGS_HIGH_PREC : 0;
01046     // set filter
01047     nh->param("nmea/filter/pos", temp, false);
01048     cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_POS : 0;
01049     nh->param("nmea/filter/msk_pos", temp, false);
01050     cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_MSK_POS : 0;
01051     nh->param("nmea/filter/time", temp, false);
01052     cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_TIME : 0;
01053     nh->param("nmea/filter/date", temp, false);
01054     cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_DATE : 0;
01055     nh->param("nmea/filter/gps_only", temp, false);
01056     cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_GPS_ONLY : 0;
01057     nh->param("nmea/filter/track", temp, false);
01058     cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_TRACK : 0;
01059     // set gnssToFilter
01060     nh->param("nmea/gnssToFilter/gps", temp, false);
01061     cfg_nmea_.gnssToFilter |= temp ? cfg_nmea_.GNSS_TO_FILTER_GPS : 0;
01062     nh->param("nmea/gnssToFilter/sbas", temp, false);
01063     cfg_nmea_.gnssToFilter |= temp ? cfg_nmea_.GNSS_TO_FILTER_SBAS : 0;
01064     nh->param("nmea/gnssToFilter/qzss", temp, false);
01065     cfg_nmea_.gnssToFilter |= temp ? cfg_nmea_.GNSS_TO_FILTER_QZSS : 0;
01066     nh->param("nmea/gnssToFilter/glonass", temp, false);
01067     cfg_nmea_.gnssToFilter |= temp ? cfg_nmea_.GNSS_TO_FILTER_GLONASS : 0;
01068     nh->param("nmea/gnssToFilter/beidou", temp, false);
01069     cfg_nmea_.gnssToFilter |= temp ? cfg_nmea_.GNSS_TO_FILTER_BEIDOU : 0;
01070 
01071     getRosUint("nmea/main_talker_id", cfg_nmea_.mainTalkerId);
01072     getRosUint("nmea/gsv_talker_id", cfg_nmea_.gsvTalkerId);
01073     
01074     std::vector<uint8_t> bdsTalkerId;
01075     getRosUint("nmea/bds_talker_id", bdsTalkerId);
01076     cfg_nmea_.bdsTalkerId[0] = bdsTalkerId[0];
01077     cfg_nmea_.bdsTalkerId[1] = bdsTalkerId[1];
01078   } 
01079 }
01080 
01081 
01082 bool UbloxFirmware8::configureUblox() {
01083   if(clear_bbr_) {
01084     // clear flash memory
01085     if(!gps.clearBbr())
01086       ROS_ERROR("u-blox failed to clear flash memory");
01087   }
01088   //
01089   // Configure the GNSS, only if the configuration is different
01090   //
01091   // First, get the current GNSS configuration
01092   ublox_msgs::CfgGNSS cfg_gnss;
01093   if (gps.poll(cfg_gnss)) {
01094     ROS_DEBUG("Read GNSS config.");
01095     ROS_DEBUG("Num. tracking channels in hardware: %i", cfg_gnss.numTrkChHw);
01096     ROS_DEBUG("Num. tracking channels to use: %i", cfg_gnss.numTrkChUse);
01097   } else {
01098     throw std::runtime_error("Failed to read the GNSS config.");
01099   }
01100 
01101   // Then, check the configuration for each GNSS. If it is different, change it.
01102   bool correct = true;
01103   for (int i = 0; i < cfg_gnss.blocks.size(); i++) {
01104     ublox_msgs::CfgGNSS_Block block = cfg_gnss.blocks[i];
01105     if (block.gnssId == block.GNSS_ID_GPS
01106         && enable_gps_ != (block.flags & block.FLAGS_ENABLE)) {
01107       correct = false;
01108       cfg_gnss.blocks[i].flags = 
01109           (cfg_gnss.blocks[i].flags & ~block.FLAGS_ENABLE) | enable_gps_;
01110       ROS_DEBUG("GPS Configuration is different");
01111     } else if (block.gnssId == block.GNSS_ID_SBAS
01112                && enable_sbas_ != (block.flags & block.FLAGS_ENABLE)) {
01113       correct = false;
01114       cfg_gnss.blocks[i].flags = 
01115           (cfg_gnss.blocks[i].flags & ~block.FLAGS_ENABLE) | enable_sbas_;
01116       ROS_DEBUG("SBAS Configuration is different");
01117     } else if (block.gnssId == block.GNSS_ID_GALILEO
01118                && enable_galileo_ != (block.flags & block.FLAGS_ENABLE)) {
01119       correct = false;
01120       cfg_gnss.blocks[i].flags = 
01121           (cfg_gnss.blocks[i].flags & ~block.FLAGS_ENABLE) | enable_galileo_;
01122       ROS_DEBUG("Galileo GNSS Configuration is different");
01123     } else if (block.gnssId == block.GNSS_ID_BEIDOU
01124                && enable_beidou_ != (block.flags & block.FLAGS_ENABLE)) {
01125       correct = false;
01126       cfg_gnss.blocks[i].flags = 
01127           (cfg_gnss.blocks[i].flags & ~enable_beidou_) | enable_beidou_;
01128       ROS_DEBUG("BeiDou Configuration is different");
01129     } else if (block.gnssId == block.GNSS_ID_IMES
01130                && enable_imes_ != (block.flags & block.FLAGS_ENABLE)) {
01131       correct = false;
01132       cfg_gnss.blocks[i].flags = 
01133           (cfg_gnss.blocks[i].flags & ~block.FLAGS_ENABLE) | enable_imes_;
01134     } else if (block.gnssId == block.GNSS_ID_QZSS
01135                && (enable_qzss_ != (block.flags & block.FLAGS_ENABLE)
01136                || (enable_qzss_ 
01137                && qzss_sig_cfg_ != (block.flags & block.FLAGS_SIG_CFG_MASK)))) {
01138       ROS_DEBUG("QZSS Configuration is different %u, %u", 
01139                 block.flags & block.FLAGS_ENABLE,
01140                 enable_qzss_);
01141       correct = false;
01142       ROS_DEBUG("QZSS Configuration: %u", block.flags);
01143       cfg_gnss.blocks[i].flags = 
01144           (cfg_gnss.blocks[i].flags & ~block.FLAGS_ENABLE) | enable_qzss_;
01145       ROS_DEBUG("QZSS Configuration: %u", cfg_gnss.blocks[i].flags);
01146       if (enable_qzss_)
01147         // Only change sig cfg if enabling
01148         cfg_gnss.blocks[i].flags |= qzss_sig_cfg_;
01149     } else if (block.gnssId == block.GNSS_ID_GLONASS
01150                && enable_glonass_ != (block.flags & block.FLAGS_ENABLE)) {
01151       correct = false;
01152       cfg_gnss.blocks[i].flags = 
01153           (cfg_gnss.blocks[i].flags & ~enable_glonass_) | enable_glonass_;
01154       ROS_DEBUG("GLONASS Configuration is different");
01155     }
01156   }
01157 
01158   // If the GNSS is already configured correctly, do not re-configure GNSS
01159   // since this requires a cold reset
01160   if (correct)
01161     ROS_DEBUG("U-Blox GNSS configuration is correct. GNSS not re-configured.");
01162   else if (!gps.configGnss(cfg_gnss, boost::posix_time::seconds(15)))
01163     throw std::runtime_error(std::string("Failed to cold reset device ") +
01164                              "after configuring GNSS");
01165 
01166   //
01167   // NMEA config
01168   //
01169   if (set_nmea_ && !gps.configure(cfg_nmea_))
01170     throw std::runtime_error("Failed to configure NMEA");
01171 
01172   return true;
01173 }
01174 
01175 void UbloxFirmware8::subscribe() {
01176   // Whether to publish Nav PVT messages
01177   nh->param("publish/nav/pvt", enabled["nav_pvt"], enabled["nav"]);
01178   // Subscribe to Nav PVT
01179   gps.subscribe<ublox_msgs::NavPVT>(
01180     boost::bind(&UbloxFirmware7Plus::callbackNavPvt, this, _1), kSubscribeRate);
01181 
01182   // Subscribe to Nav SAT messages
01183   nh->param("publish/nav/sat", enabled["nav_sat"], enabled["nav"]);
01184   if (enabled["nav_sat"])
01185     gps.subscribe<ublox_msgs::NavSAT>(boost::bind(
01186         publish<ublox_msgs::NavSAT>, _1, "navsat"), kNavSvInfoSubscribeRate);
01187 
01188   // Subscribe to Mon HW
01189   nh->param("publish/mon/hw", enabled["mon_hw"], enabled["mon"]);
01190   if (enabled["mon_hw"])
01191     gps.subscribe<ublox_msgs::MonHW>(boost::bind(
01192         publish<ublox_msgs::MonHW>, _1, "monhw"), kSubscribeRate);
01193 
01194   // Subscribe to RTCM messages
01195   nh->param("publish/rxm/rtcm", enabled["rxm_rtcm"], enabled["rxm"]);
01196   if (enabled["rxm_rtcm"])
01197     gps.subscribe<ublox_msgs::RxmRTCM>(boost::bind(
01198         publish<ublox_msgs::RxmRTCM>, _1, "rxmrtcm"), kSubscribeRate);
01199 }
01200 
01201 //
01202 // Raw Data Products
01203 //
01204 void RawDataProduct::subscribe() {
01205   // Defaults to true instead of to all
01206   nh->param("publish/rxm/all", enabled["rxm"], true);
01207 
01208   // Subscribe to RXM Raw
01209   nh->param("publish/rxm/raw", enabled["rxm_raw"], enabled["rxm"]);
01210   if (enabled["rxm_raw"])
01211     gps.subscribe<ublox_msgs::RxmRAW>(boost::bind(
01212         publish<ublox_msgs::RxmRAW>, _1, "rxmraw"), kSubscribeRate);
01213 
01214   // Subscribe to RXM SFRB
01215   nh->param("publish/rxm/sfrb", enabled["rxm_sfrb"], enabled["rxm"]);
01216   if (enabled["rxm_sfrb"])
01217     gps.subscribe<ublox_msgs::RxmSFRB>(boost::bind(
01218         publish<ublox_msgs::RxmSFRB>, _1, "rxmsfrb"), kSubscribeRate);
01219 
01220   // Subscribe to RXM EPH
01221   nh->param("publish/rxm/eph", enabled["rxm_eph"], enabled["rxm"]);
01222   if (enabled["rxm_eph"])
01223     gps.subscribe<ublox_msgs::RxmEPH>(boost::bind(
01224         publish<ublox_msgs::RxmEPH>, _1, "rxmeph"), kSubscribeRate);
01225 
01226   // Subscribe to RXM ALM
01227   nh->param("publish/rxm/almRaw", enabled["rxm_alm"], enabled["rxm"]);
01228   if (enabled["rxm_alm"])
01229     gps.subscribe<ublox_msgs::RxmALM>(boost::bind(
01230         publish<ublox_msgs::RxmALM>, _1, "rxmalm"), kSubscribeRate);
01231 }
01232 
01233 void RawDataProduct::initializeRosDiagnostics() {
01234   if (enabled["rxm_raw"])
01235     freq_diagnostics_.push_back(UbloxTopicDiagnostic("rxmraw", kRtcmFreqTol, 
01236                                                kRtcmFreqWindow));
01237   if (enabled["rxm_sfrb"])
01238     freq_diagnostics_.push_back(UbloxTopicDiagnostic("rxmsfrb", kRtcmFreqTol, 
01239                                                kRtcmFreqWindow));
01240   if (enabled["rxm_eph"])
01241     freq_diagnostics_.push_back(UbloxTopicDiagnostic("rxmeph", kRtcmFreqTol, 
01242                                                kRtcmFreqWindow));
01243   if (enabled["rxm_alm"])
01244     freq_diagnostics_.push_back(UbloxTopicDiagnostic("rxmalm", kRtcmFreqTol, 
01245                                                kRtcmFreqWindow));
01246 }
01247 
01248 //
01249 // u-blox ADR devices, partially implemented
01250 //
01251 void AdrUdrProduct::getRosParams() {
01252   nh->param("use_adr", use_adr_, true);
01253   // Check the nav rate
01254   float nav_rate_hz = 1000 / (meas_rate * nav_rate);
01255   if(nav_rate_hz != 1)
01256     ROS_WARN("Nav Rate recommended to be 1 Hz");
01257 }
01258 
01259 bool AdrUdrProduct::configureUblox() {
01260   if(!gps.setUseAdr(use_adr_))
01261     throw std::runtime_error(std::string("Failed to ") 
01262                              + (use_adr_ ? "enable" : "disable") + "use_adr");
01263   return true;
01264 }
01265 
01266 void AdrUdrProduct::subscribe() {
01267   nh->param("publish/esf/all", enabled["esf"], true);
01268 
01269   // Subscribe to NAV ATT messages
01270   nh->param("publish/nav/att", enabled["nav_att"], enabled["nav"]);
01271   if (enabled["nav_att"])
01272     gps.subscribe<ublox_msgs::NavATT>(boost::bind(
01273         publish<ublox_msgs::NavATT>, _1, "navatt"), kSubscribeRate);
01274 
01275   // Subscribe to ESF INS messages
01276   nh->param("publish/esf/ins", enabled["esf_ins"], enabled["esf"]);
01277   if (enabled["esf_ins"])
01278     gps.subscribe<ublox_msgs::EsfINS>(boost::bind(
01279         publish<ublox_msgs::EsfINS>, _1, "esfins"), kSubscribeRate);
01280 
01281   // Subscribe to ESF Meas messages
01282   nh->param("publish/esf/meas", enabled["esf_meas"], enabled["esf"]);
01283   if (enabled["esf_meas"])
01284     gps.subscribe<ublox_msgs::EsfMEAS>(boost::bind(
01285         publish<ublox_msgs::EsfMEAS>, _1, "esfmeas"), kSubscribeRate);
01286 
01287   // Subscribe to ESF Raw messages
01288   nh->param("publish/esf/raw", enabled["esf_raw"], enabled["esf"]);
01289   if (enabled["esf_raw"])
01290     gps.subscribe<ublox_msgs::EsfRAW>(boost::bind(
01291         publish<ublox_msgs::EsfRAW>, _1, "esfraw"), kSubscribeRate);
01292 
01293   // Subscribe to ESF Status messages
01294   nh->param("publish/esf/status", enabled["esf_status"], enabled["esf"]);
01295   if (enabled["esf_status"])
01296     gps.subscribe<ublox_msgs::EsfSTATUS>(boost::bind(
01297         publish<ublox_msgs::EsfSTATUS>, _1, "esfstatus"), kSubscribeRate);
01298 
01299   // Subscribe to HNR PVT messages
01300   nh->param("publish/hnr/pvt", enabled["hnr_pvt"], true);
01301   if (enabled["hnr_pvt"])
01302     gps.subscribe<ublox_msgs::HnrPVT>(boost::bind(
01303         publish<ublox_msgs::HnrPVT>, _1, "hnrpvt"), kSubscribeRate);
01304 }
01305 
01306 //
01307 // u-blox High Precision GNSS Reference Station
01308 //
01309 void HpgRefProduct::getRosParams() {
01310   if(nav_rate * meas_rate != 1000)
01311     ROS_WARN("For HPG Ref devices, nav_rate should be exactly 1 Hz.");
01312 
01313   if(!getRosUint("tmode3", tmode3_))
01314     throw std::runtime_error("Invalid settings: TMODE3 must be set");
01315 
01316   if(tmode3_ == ublox_msgs::CfgTMODE3::FLAGS_MODE_FIXED) {
01317     if(!nh->getParam("arp/position", arp_position_))
01318       throw std::runtime_error(std::string("Invalid settings: arp/position ") 
01319                                + "must be set if TMODE3 is fixed");
01320     if(!getRosInt("arp/position_hp", arp_position_hp_))
01321       throw std::runtime_error(std::string("Invalid settings: arp/position_hp ") 
01322                                + "must be set if TMODE3 is fixed");
01323     if(!nh->getParam("arp/acc", fixed_pos_acc_))
01324       throw std::runtime_error(std::string("Invalid settings: arp/acc ") 
01325                                + "must be set if TMODE3 is fixed");
01326     if(!nh->getParam("arp/lla_flag", lla_flag_)) {
01327       ROS_WARN("arp/lla_flag param not set, assuming ARP coordinates are %s",
01328                "in ECEF");
01329       lla_flag_ = false;
01330     }
01331   } else if(tmode3_ == ublox_msgs::CfgTMODE3::FLAGS_MODE_SURVEY_IN) {
01332     nh->param("sv_in/reset", svin_reset_, true);
01333     if(!getRosUint("sv_in/min_dur", sv_in_min_dur_))
01334       throw std::runtime_error(std::string("Invalid settings: sv_in/min_dur ") 
01335                                + "must be set if TMODE3 is survey-in");
01336     if(!nh->getParam("sv_in/acc_lim", sv_in_acc_lim_))
01337       throw std::runtime_error(std::string("Invalid settings: sv_in/acc_lim ") 
01338                                + "must be set if TMODE3 is survey-in");
01339   } else if(tmode3_ != ublox_msgs::CfgTMODE3::FLAGS_MODE_DISABLED) {
01340     throw std::runtime_error(std::string("tmode3 param invalid. See CfgTMODE3") 
01341                              + " flag constants for possible values.");
01342   }
01343 }
01344 
01345 bool HpgRefProduct::configureUblox() {
01346   // Configure TMODE3
01347   if(tmode3_ == ublox_msgs::CfgTMODE3::FLAGS_MODE_DISABLED) {
01348     if(!gps.disableTmode3())
01349       throw std::runtime_error("Failed to disable TMODE3.");
01350     mode_ = DISABLED;
01351   } else if(tmode3_ == ublox_msgs::CfgTMODE3::FLAGS_MODE_FIXED) {
01352     if(!gps.configTmode3Fixed(lla_flag_, arp_position_, arp_position_hp_, 
01353                                fixed_pos_acc_))
01354       throw std::runtime_error("Failed to set TMODE3 to fixed.");
01355     if(!gps.configRtcm(rtcm_ids, rtcm_rates))
01356       throw std::runtime_error("Failed to set RTCM rates");
01357     mode_ = FIXED;
01358   } else if(tmode3_ == ublox_msgs::CfgTMODE3::FLAGS_MODE_SURVEY_IN) {
01359     if(!svin_reset_) {
01360       ublox_msgs::NavSVIN nav_svin;
01361       if(!gps.poll(nav_svin))
01362         throw std::runtime_error(std::string("Failed to poll NavSVIN while") +
01363                                  " configuring survey-in");
01364       // Don't reset survey-in if it's already active
01365       if(nav_svin.active) {
01366         mode_ = SURVEY_IN;
01367         return true;
01368       }
01369       // Don't reset survey-in if it already has a valid value
01370       if(nav_svin.valid) {
01371         setTimeMode();
01372         return true;
01373       }
01374       ublox_msgs::NavPVT nav_pvt;
01375       if(!gps.poll(nav_pvt))
01376         throw std::runtime_error(std::string("Failed to poll NavPVT while") + 
01377                                  " configuring survey-in");
01378       // Don't reset survey in if in time mode with a good fix
01379       if (nav_pvt.fixType == nav_pvt.FIX_TYPE_TIME_ONLY 
01380           && nav_pvt.flags & nav_pvt.FLAGS_GNSS_FIX_OK) {
01381         setTimeMode();
01382         return true;
01383       }
01384     }
01385     // Reset the Survey In    
01386     // For Survey in, meas rate must be at least 1 Hz
01387     uint16_t meas_rate_temp = meas_rate < 1000 ? meas_rate : 1000; // [ms]
01388     // If measurement period isn't a factor of 1000, set to default
01389     if(1000 % meas_rate_temp != 0)
01390       meas_rate_temp = kDefaultMeasPeriod;
01391     // Set nav rate to 1 Hz during survey in
01392     if(!gps.configRate(meas_rate_temp, (int) 1000 / meas_rate_temp))
01393       throw std::runtime_error(std::string("Failed to set nav rate to 1 Hz") +
01394                                "before setting TMODE3 to survey-in.");
01395     // As recommended in the documentation, first disable, then set to survey in
01396     if(!gps.disableTmode3())
01397       ROS_ERROR("Failed to disable TMODE3 before setting to survey-in.");
01398     else 
01399       mode_ = DISABLED;
01400     // Set to Survey in mode
01401     if(!gps.configTmode3SurveyIn(sv_in_min_dur_, sv_in_acc_lim_))
01402       throw std::runtime_error("Failed to set TMODE3 to survey-in.");
01403     mode_ = SURVEY_IN;
01404   }
01405   return true;
01406 }
01407 
01408 void HpgRefProduct::subscribe() {
01409   // Whether to publish Nav Survey-In messages
01410   nh->param("publish/nav/svin", enabled["nav_svin"], enabled["nav"]);
01411   // Subscribe to Nav Survey-In
01412   gps.subscribe<ublox_msgs::NavSVIN>(boost::bind(
01413       &HpgRefProduct::callbackNavSvIn, this, _1), kSubscribeRate);
01414 }
01415 
01416 void HpgRefProduct::callbackNavSvIn(ublox_msgs::NavSVIN m) {
01417   if(enabled["nav_svin"]) {
01418     static ros::Publisher publisher = 
01419         nh->advertise<ublox_msgs::NavSVIN>("navsvin", kROSQueueSize);
01420     publisher.publish(m);
01421   }
01422 
01423   last_nav_svin_ = m;
01424 
01425   if(!m.active && m.valid && mode_ == SURVEY_IN) {
01426     setTimeMode();
01427   }
01428 
01429   updater->update();
01430 }
01431 
01432 bool HpgRefProduct::setTimeMode() {
01433   ROS_INFO("Setting mode (internal state) to Time Mode");
01434   mode_ = TIME;
01435 
01436   // Set the Measurement & nav rate to user config 
01437   // (survey-in sets nav_rate to 1 Hz regardless of user setting)
01438   if(!gps.configRate(meas_rate, nav_rate))
01439     ROS_ERROR("Failed to set measurement rate to %d ms %s %d", meas_rate, 
01440               "navigation rate to ", nav_rate);
01441   // Enable the RTCM out messages
01442   if(!gps.configRtcm(rtcm_ids, rtcm_rates)) {
01443     ROS_ERROR("Failed to configure RTCM IDs");
01444     return false;
01445   }
01446   return true;
01447 }
01448 
01449 void HpgRefProduct::initializeRosDiagnostics() {
01450   updater->add("TMODE3", this, &HpgRefProduct::tmode3Diagnostics);
01451   updater->force_update();
01452 }
01453 
01454 void HpgRefProduct::tmode3Diagnostics(
01455     diagnostic_updater::DiagnosticStatusWrapper& stat) {
01456   if (mode_ == INIT) {
01457     stat.level = diagnostic_msgs::DiagnosticStatus::WARN;
01458     stat.message = "Not configured";
01459   } else if (mode_ == DISABLED){
01460     stat.level = diagnostic_msgs::DiagnosticStatus::WARN;
01461     stat.message = "Disabled";
01462   } else if (mode_ == SURVEY_IN) {
01463     if (!last_nav_svin_.active && !last_nav_svin_.valid) {
01464       stat.level = diagnostic_msgs::DiagnosticStatus::ERROR;
01465       stat.message = "Survey-In inactive and invalid";
01466     } else if (last_nav_svin_.active && !last_nav_svin_.valid) {
01467       stat.level = diagnostic_msgs::DiagnosticStatus::WARN;
01468       stat.message = "Survey-In active but invalid";
01469     } else if (!last_nav_svin_.active && last_nav_svin_.valid) {
01470       stat.level = diagnostic_msgs::DiagnosticStatus::OK;
01471       stat.message = "Survey-In complete";
01472     } else if (last_nav_svin_.active && last_nav_svin_.valid) {
01473       stat.level = diagnostic_msgs::DiagnosticStatus::OK;
01474       stat.message = "Survey-In active and valid";
01475     }
01476     
01477     stat.add("iTOW [ms]", last_nav_svin_.iTOW);
01478     stat.add("Duration [s]", last_nav_svin_.dur);
01479     stat.add("# observations", last_nav_svin_.obs);
01480     stat.add("Mean X [m]", last_nav_svin_.meanX * 1e-2);
01481     stat.add("Mean Y [m]", last_nav_svin_.meanY * 1e-2);
01482     stat.add("Mean Z [m]", last_nav_svin_.meanZ * 1e-2);
01483     stat.add("Mean X HP [m]", last_nav_svin_.meanXHP * 1e-4);
01484     stat.add("Mean Y HP [m]", last_nav_svin_.meanYHP * 1e-4);
01485     stat.add("Mean Z HP [m]", last_nav_svin_.meanZHP * 1e-4);
01486     stat.add("Mean Accuracy [m]", last_nav_svin_.meanAcc * 1e-4);
01487   } else if(mode_ == FIXED) {
01488     stat.level = diagnostic_msgs::DiagnosticStatus::OK;
01489     stat.message = "Fixed Position";
01490   } else if(mode_ == TIME) {
01491     stat.level = diagnostic_msgs::DiagnosticStatus::OK;
01492     stat.message = "Time";
01493   }
01494 }
01495 
01496 //
01497 // U-Blox High Precision GNSS Rover
01498 //
01499 void HpgRovProduct::getRosParams() {
01500   // default to float, see CfgDGNSS message for details
01501   getRosUint("dgnss_mode", dgnss_mode_, 
01502               ublox_msgs::CfgDGNSS::DGNSS_MODE_RTK_FIXED); 
01503 }
01504 
01505 bool HpgRovProduct::configureUblox() {
01506   // Configure the DGNSS
01507   if(!gps.setDgnss(dgnss_mode_))
01508     throw std::runtime_error(std::string("Failed to Configure DGNSS"));
01509   return true;
01510 }
01511 
01512 void HpgRovProduct::subscribe() {
01513   // Whether to publish Nav Relative Position NED
01514   nh->param("publish/nav/relposned", enabled["nav_relposned"], enabled["nav"]);
01515   // Subscribe to Nav Relative Position NED messages (also updates diagnostics)
01516   gps.subscribe<ublox_msgs::NavRELPOSNED>(boost::bind(
01517      &HpgRovProduct::callbackNavRelPosNed, this, _1), kSubscribeRate);
01518 }
01519 
01520 void HpgRovProduct::initializeRosDiagnostics() {
01521   freq_rtcm_ = UbloxTopicDiagnostic(std::string("rxmrtcm"), 
01522                                kRtcmFreqMin, kRtcmFreqMax,
01523                                kRtcmFreqTol, kRtcmFreqWindow);
01524   updater->add("Carrier Phase Solution", this, 
01525                 &HpgRovProduct::carrierPhaseDiagnostics);
01526   updater->force_update();
01527 }
01528 
01529 void HpgRovProduct::carrierPhaseDiagnostics(
01530     diagnostic_updater::DiagnosticStatusWrapper& stat) {
01531   uint32_t carr_soln = last_rel_pos_.flags & last_rel_pos_.FLAGS_CARR_SOLN_MASK;
01532   stat.add("iTow", last_rel_pos_.iTow);
01533   if (carr_soln & last_rel_pos_.FLAGS_CARR_SOLN_NONE ||
01534       !(last_rel_pos_.flags & last_rel_pos_.FLAGS_DIFF_SOLN &&
01535         last_rel_pos_.flags & last_rel_pos_.FLAGS_REL_POS_VALID)) {
01536     stat.level = diagnostic_msgs::DiagnosticStatus::ERROR;
01537     stat.message = "None";
01538   } else {
01539     if (carr_soln & last_rel_pos_.FLAGS_CARR_SOLN_FLOAT) {
01540       stat.level = diagnostic_msgs::DiagnosticStatus::WARN;
01541       stat.message = "Float";    
01542     } else if (carr_soln & last_rel_pos_.FLAGS_CARR_SOLN_FIXED) {
01543       stat.level = diagnostic_msgs::DiagnosticStatus::OK;
01544       stat.message = "Fixed";    
01545     }
01546     stat.add("Ref Station ID", last_rel_pos_.refStationId);
01547 
01548     double rel_pos_n = (last_rel_pos_.relPosN 
01549                        + (last_rel_pos_.relPosHPN * 1e-2)) * 1e-2;
01550     double rel_pos_e = (last_rel_pos_.relPosE 
01551                        + (last_rel_pos_.relPosHPE * 1e-2)) * 1e-2;
01552     double rel_pos_d = (last_rel_pos_.relPosD 
01553                        + (last_rel_pos_.relPosHPD * 1e-2)) * 1e-2;
01554     stat.add("Relative Position N [m]", rel_pos_n);
01555     stat.add("Relative Accuracy N [m]", last_rel_pos_.accN * 1e-4);
01556     stat.add("Relative Position E [m]", rel_pos_e);
01557     stat.add("Relative Accuracy E [m]", last_rel_pos_.accE * 1e-4);
01558     stat.add("Relative Position D [m]", rel_pos_d);
01559     stat.add("Relative Accuracy D [m]", last_rel_pos_.accD * 1e-4);
01560   }
01561 }
01562 
01563 void HpgRovProduct::callbackNavRelPosNed(const ublox_msgs::NavRELPOSNED &m) {
01564   if (enabled["nav_relposned"]) {
01565     static ros::Publisher publisher = 
01566         nh->advertise<ublox_msgs::NavRELPOSNED>("navrelposned", kROSQueueSize);
01567     publisher.publish(m);
01568   }
01569 
01570   last_rel_pos_ = m;
01571   updater->update();
01572 }
01573 
01574 //
01575 // U-Blox Time Sync Products, partially implemented.
01576 //
01577 void TimProduct::subscribe() {
01578   // Subscribe to RawX messages
01579   nh->param("publish/rxm/raw", enabled["rxm_raw"], enabled["rxm"]);
01580   if (enabled["rxm_raw"])
01581     gps.subscribe<ublox_msgs::RxmRAWX>(boost::bind(
01582         publish<ublox_msgs::RxmRAWX>, _1, "rxmraw"), kSubscribeRate);
01583 
01584   // Subscribe to SFRBX messages
01585   nh->param("publish/rxm/sfrb", enabled["rxm_sfrb"], enabled["rxm"]);
01586   if (enabled["rxm_sfrb"])
01587     gps.subscribe<ublox_msgs::RxmSFRBX>(boost::bind(
01588         publish<ublox_msgs::RxmSFRBX>, _1, "rxmsfrb"), kSubscribeRate);
01589 }
01590 
01591 int main(int argc, char** argv) {
01592   ros::init(argc, argv, "ublox_gps");
01593   nh.reset(new ros::NodeHandle("~"));
01594   nh->param("debug", ublox_gps::debug, 1);
01595   if(ublox_gps::debug) {
01596     if (ros::console::set_logger_level(ROSCONSOLE_DEFAULT_NAME, 
01597                                        ros::console::levels::Debug))
01598      ros::console::notifyLoggerLevelsChanged();
01599    
01600   }
01601   UbloxNode node;
01602   return 0;
01603 }


ublox_gps
Author(s): Johannes Meyer
autogenerated on Fri Aug 11 2017 02:31:06