00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include <ublox_gps/gps.h>
00031
00032 namespace ublox_gps {
00033
00034 using namespace ublox_msgs;
00035
00036 boost::posix_time::time_duration Gps::default_timeout_(
00037 boost::posix_time::seconds(Gps::kDefaultAckTimeout));
00038
00039 Gps::Gps() : configured_(false) { subscribeAcks(); }
00040
00041 Gps::~Gps() { close(); }
00042
00043 void Gps::setWorker(const boost::shared_ptr<Worker>& worker) {
00044 if (worker_) return;
00045 worker_ = worker;
00046 worker_->setCallback(boost::bind(&CallbackHandlers::readCallback,
00047 &callbacks_, _1, _2));
00048 configured_ = static_cast<bool>(worker);
00049 }
00050
00051 void Gps::subscribeAcks() {
00052
00053 subscribeId<ublox_msgs::Ack>(boost::bind(&Gps::processNack, this, _1),
00054 ublox_msgs::Message::ACK::NACK);
00055
00056 subscribeId<ublox_msgs::Ack>(boost::bind(&Gps::processAck, this, _1),
00057 ublox_msgs::Message::ACK::ACK);
00058
00059 subscribe<ublox_msgs::UpdSOS_Ack>(
00060 boost::bind(&Gps::processUpdSosAck, this, _1));
00061 }
00062
00063 void Gps::processAck(const ublox_msgs::Ack &m) {
00064
00065 Ack ack;
00066 ack.type = ACK;
00067 ack.class_id = m.clsID;
00068 ack.msg_id = m.msgID;
00069
00070 ack_.store(ack, boost::memory_order_seq_cst);
00071 ROS_DEBUG_COND(debug >= 2, "U-blox: received ACK: 0x%02x / 0x%02x",
00072 m.clsID, m.msgID);
00073 }
00074
00075 void Gps::processNack(const ublox_msgs::Ack &m) {
00076
00077 Ack ack;
00078 ack.type = NACK;
00079 ack.class_id = m.clsID;
00080 ack.msg_id = m.msgID;
00081
00082 ack_.store(ack, boost::memory_order_seq_cst);
00083 ROS_ERROR("U-blox: received NACK: 0x%02x / 0x%02x", m.clsID, m.msgID);
00084 }
00085
00086 void Gps::processUpdSosAck(const ublox_msgs::UpdSOS_Ack &m) {
00087 if (m.cmd == UpdSOS_Ack::CMD_BACKUP_CREATE_ACK) {
00088 Ack ack;
00089 ack.type = (m.response == m.BACKUP_CREATE_ACK) ? ACK : NACK;
00090 ack.class_id = m.CLASS_ID;
00091 ack.msg_id = m.MESSAGE_ID;
00092
00093 ack_.store(ack, boost::memory_order_seq_cst);
00094 ROS_DEBUG_COND(ack.type == ACK && debug >= 2,
00095 "U-blox: received UPD SOS Backup ACK");
00096 if(ack.type == NACK)
00097 ROS_ERROR("U-blox: received UPD SOS Backup NACK");
00098 }
00099 }
00100
00101 void Gps::initializeSerial(std::string port, unsigned int baudrate,
00102 uint16_t uart_in, uint16_t uart_out) {
00103 port_ = port;
00104 boost::shared_ptr<boost::asio::io_service> io_service(
00105 new boost::asio::io_service);
00106 boost::shared_ptr<boost::asio::serial_port> serial(
00107 new boost::asio::serial_port(*io_service));
00108
00109
00110 try {
00111 serial->open(port);
00112 } catch (std::runtime_error& e) {
00113 throw std::runtime_error("U-Blox: Could not open serial port :"
00114 + port + " " + e.what());
00115 }
00116
00117 ROS_INFO("U-Blox: Opened serial port %s", port.c_str());
00118
00119
00120 if (worker_) return;
00121 setWorker(boost::shared_ptr<Worker>(
00122 new AsyncWorker<boost::asio::serial_port>(serial, io_service)));
00123
00124 configured_ = false;
00125
00126
00127 boost::asio::serial_port_base::baud_rate current_baudrate;
00128 serial->get_option(current_baudrate);
00129
00130 for (int i = 0; i < sizeof(kBaudrates)/sizeof(kBaudrates[0]); i++) {
00131 if (current_baudrate.value() == baudrate)
00132 break;
00133
00134 if(current_baudrate.value() > kBaudrates[i] && baudrate > kBaudrates[i])
00135 continue;
00136 serial->set_option(
00137 boost::asio::serial_port_base::baud_rate(kBaudrates[i]));
00138 boost::this_thread::sleep(
00139 boost::posix_time::milliseconds(kSetBaudrateSleepMs));
00140 serial->get_option(current_baudrate);
00141 ROS_DEBUG("U-Blox: Set ASIO baudrate to %u", current_baudrate.value());
00142 }
00143 configured_ = configUart1(baudrate, uart_in, uart_out);
00144 if(!configured_ || current_baudrate.value() != baudrate) {
00145 throw std::runtime_error("Could not configure serial baud rate");
00146 }
00147 }
00148
00149 void Gps::resetSerial(std::string port) {
00150 boost::shared_ptr<boost::asio::io_service> io_service(
00151 new boost::asio::io_service);
00152 boost::shared_ptr<boost::asio::serial_port> serial(
00153 new boost::asio::serial_port(*io_service));
00154
00155
00156 try {
00157 serial->open(port);
00158 } catch (std::runtime_error& e) {
00159 throw std::runtime_error("U-Blox: Could not open serial port :"
00160 + port + " " + e.what());
00161 }
00162
00163 ROS_INFO("U-Blox: Reset serial port %s", port.c_str());
00164
00165
00166 if (worker_) return;
00167 setWorker(boost::shared_ptr<Worker>(
00168 new AsyncWorker<boost::asio::serial_port>(serial, io_service)));
00169 configured_ = false;
00170
00171
00172 std::vector<uint8_t> payload;
00173 payload.push_back(CfgPRT::PORT_ID_UART1);
00174 if (!poll(CfgPRT::CLASS_ID, CfgPRT::MESSAGE_ID, payload)) {
00175 ROS_ERROR("Resetting Serial Port: Could not poll UART1 CfgPRT");
00176 return;
00177 }
00178 CfgPRT prt;
00179 if(!read(prt, default_timeout_)) {
00180 ROS_ERROR("Resetting Serial Port: Could not read polled UART1 CfgPRT %s",
00181 "message");
00182 return;
00183 }
00184
00185
00186 serial->set_option(boost::asio::serial_port_base::baud_rate(prt.baudRate));
00187 configured_ = true;
00188 }
00189
00190 void Gps::initializeTcp(std::string host, std::string port) {
00191 host_ = host;
00192 port_ = port;
00193 boost::shared_ptr<boost::asio::io_service> io_service(
00194 new boost::asio::io_service);
00195 boost::asio::ip::tcp::resolver::iterator endpoint;
00196
00197 try {
00198 boost::asio::ip::tcp::resolver resolver(*io_service);
00199 endpoint =
00200 resolver.resolve(boost::asio::ip::tcp::resolver::query(host, port));
00201 } catch (std::runtime_error& e) {
00202 throw std::runtime_error("U-Blox: Could not resolve" + host + " " +
00203 port + " " + e.what());
00204 }
00205
00206 boost::shared_ptr<boost::asio::ip::tcp::socket> socket(
00207 new boost::asio::ip::tcp::socket(*io_service));
00208
00209 try {
00210 socket->connect(*endpoint);
00211 } catch (std::runtime_error& e) {
00212 throw std::runtime_error("U-Blox: Could not connect to " +
00213 endpoint->host_name() + ":" +
00214 endpoint->service_name() + ": " + e.what());
00215 }
00216
00217 ROS_INFO("U-Blox: Connected to %s:%s.", endpoint->host_name().c_str(),
00218 endpoint->service_name().c_str());
00219
00220 if (worker_) return;
00221 setWorker(boost::shared_ptr<Worker>(
00222 new AsyncWorker<boost::asio::ip::tcp::socket>(socket,
00223 io_service)));
00224 }
00225
00226 void Gps::close() {
00227 if(save_on_shutdown_) {
00228 if(saveOnShutdown())
00229 ROS_INFO("U-Blox Flash BBR saved");
00230 else
00231 ROS_INFO("U-Blox Flash BBR failed to save");
00232 }
00233 worker_.reset();
00234 configured_ = false;
00235 }
00236
00237 void Gps::reset(const boost::posix_time::time_duration& wait) {
00238 worker_.reset();
00239 configured_ = false;
00240
00241 boost::this_thread::sleep(wait);
00242 if (host_ == "")
00243 resetSerial(port_);
00244 else
00245 initializeTcp(host_, port_);
00246 }
00247
00248 bool Gps::configReset(uint16_t nav_bbr_mask, uint16_t reset_mode) {
00249 ROS_WARN("Resetting u-blox. If device address changes, %s",
00250 "node must be relaunched.");
00251
00252 CfgRST rst;
00253 rst.navBbrMask = nav_bbr_mask;
00254 rst.resetMode = reset_mode;
00255
00256
00257 if (!configure(rst, false))
00258 return false;
00259 return true;
00260 }
00261
00262 bool Gps::configGnss(CfgGNSS gnss,
00263 const boost::posix_time::time_duration& wait) {
00264
00265 ROS_DEBUG("Re-configuring GNSS.");
00266 if (!configure(gnss))
00267 return false;
00268
00269 ROS_WARN("GNSS re-configured, cold resetting device.");
00270 if (!configReset(CfgRST::NAV_BBR_COLD_START, CfgRST::RESET_MODE_GNSS))
00271 return false;
00272 ros::Duration(1.0).sleep();
00273
00274 reset(wait);
00275 return isConfigured();
00276 }
00277
00278 bool Gps::saveOnShutdown() {
00279
00280 CfgRST rst;
00281 rst.navBbrMask = rst.NAV_BBR_HOT_START;
00282 rst.resetMode = rst.RESET_MODE_GNSS_STOP;
00283 if(!configure(rst))
00284 return false;
00285
00286
00287 UpdSOS backup;
00288 return configure(backup);
00289 }
00290
00291 bool Gps::clearBbr() {
00292
00293
00294 UpdSOS sos;
00295 sos.cmd = sos.CMD_FLASH_BACKUP_CLEAR;
00296 return configure(sos);
00297 }
00298
00299 bool Gps::configUart1(unsigned int baudrate, uint16_t in_proto_mask,
00300 uint16_t out_proto_mask) {
00301 if (!worker_) return true;
00302
00303 ROS_DEBUG("Configuring UART1 baud rate: %u, In/Out Protocol: %u / %u",
00304 baudrate, in_proto_mask, out_proto_mask);
00305
00306 CfgPRT port;
00307 port.portID = CfgPRT::PORT_ID_UART1;
00308 port.baudRate = baudrate;
00309 port.mode = CfgPRT::MODE_RESERVED1 | CfgPRT::MODE_CHAR_LEN_8BIT |
00310 CfgPRT::MODE_PARITY_NO | CfgPRT::MODE_STOP_BITS_1;
00311 port.inProtoMask = in_proto_mask;
00312 port.outProtoMask = out_proto_mask;
00313 return configure(port);
00314 }
00315
00316 bool Gps::disableUart1(CfgPRT& prev_config) {
00317 ROS_DEBUG("Disabling UART1");
00318
00319
00320 std::vector<uint8_t> payload;
00321 payload.push_back(CfgPRT::PORT_ID_UART1);
00322 if (!poll(CfgPRT::CLASS_ID, CfgPRT::MESSAGE_ID, payload)) {
00323 ROS_ERROR("disableUart: Could not poll UART1 CfgPRT");
00324 return false;
00325 }
00326 if(!read(prev_config, default_timeout_)) {
00327 ROS_ERROR("disableUart: Could not read polled UART1 CfgPRT message");
00328 return false;
00329 }
00330
00331 CfgPRT port;
00332 port.portID = CfgPRT::PORT_ID_UART1;
00333 port.mode = prev_config.mode;
00334 port.baudRate = prev_config.baudRate;
00335 port.inProtoMask = 0;
00336 port.outProtoMask = 0;
00337 port.txReady = prev_config.txReady;
00338 port.flags = prev_config.flags;
00339 return configure(port);
00340 }
00341
00342 bool Gps::configUsb(uint16_t tx_ready,
00343 uint16_t in_proto_mask,
00344 uint16_t out_proto_mask) {
00345 if (!worker_) return true;
00346
00347 ROS_DEBUG("Configuring USB tx_ready: %u, In/Out Protocol: %u / %u",
00348 tx_ready, in_proto_mask, out_proto_mask);
00349
00350 CfgPRT port;
00351 port.portID = CfgPRT::PORT_ID_USB;
00352 port.txReady = tx_ready;
00353 port.inProtoMask = in_proto_mask;
00354 port.outProtoMask = out_proto_mask;
00355 return configure(port);
00356 }
00357
00358 bool Gps::configRate(uint16_t meas_rate, uint16_t nav_rate) {
00359 ROS_DEBUG("Configuring measurement rate to %u and nav rate to %u", meas_rate,
00360 nav_rate);
00361
00362 CfgRATE rate;
00363 rate.measRate = meas_rate;
00364 rate.navRate = nav_rate;
00365 rate.timeRef = CfgRATE::TIME_REF_GPS;
00366 return configure(rate);
00367 }
00368
00369 bool Gps::configRtcm(std::vector<uint8_t> ids, std::vector<uint8_t> rates) {
00370 for(size_t i = 0; i < ids.size(); ++i) {
00371 ROS_DEBUG("Setting RTCM %d Rate %u", ids[i], rates[i]);
00372 if(!setRate(ublox_msgs::Class::RTCM, (uint8_t)ids[i], rates[i])) {
00373 ROS_ERROR("Could not set RTCM %d to rate %u", ids[i], rates[i]);
00374 return false;
00375 }
00376 }
00377 return true;
00378 }
00379
00380 bool Gps::configSbas(bool enable, uint8_t usage, uint8_t max_sbas) {
00381 ROS_DEBUG("Configuring SBAS: usage %u, max_sbas %u", usage, max_sbas);
00382
00383 ublox_msgs::CfgSBAS msg;
00384 msg.mode = (enable ? CfgSBAS::MODE_ENABLED : 0);
00385 msg.usage = usage;
00386 msg.maxSBAS = max_sbas;
00387 return configure(msg);
00388 }
00389
00390 bool Gps::configTmode3Fixed(bool lla_flag,
00391 std::vector<float> arp_position,
00392 std::vector<int8_t> arp_position_hp,
00393 float fixed_pos_acc) {
00394 if(arp_position.size() != 3 || arp_position_hp.size() != 3) {
00395 ROS_ERROR("Configuring TMODE3 to Fixed: size of position %s",
00396 "& arp_position_hp args must be 3");
00397 return false;
00398 }
00399
00400 ROS_DEBUG("Configuring TMODE3 to Fixed");
00401
00402 CfgTMODE3 tmode3;
00403 tmode3.flags = tmode3.FLAGS_MODE_FIXED & tmode3.FLAGS_MODE_MASK;
00404 tmode3.flags |= lla_flag ? tmode3.FLAGS_LLA : 0;
00405
00406
00407 if(lla_flag) {
00408
00409 tmode3.ecefXOrLat = (int)round(arp_position[0] * 1e7);
00410 tmode3.ecefYOrLon = (int)round(arp_position[1] * 1e7);
00411 tmode3.ecefZOrAlt = (int)round(arp_position[2] * 1e7);
00412 } else {
00413
00414 tmode3.ecefXOrLat = (int)round(arp_position[0] * 1e2);
00415 tmode3.ecefYOrLon = (int)round(arp_position[1] * 1e2);
00416 tmode3.ecefZOrAlt = (int)round(arp_position[2] * 1e2);
00417 }
00418 tmode3.ecefXOrLatHP = arp_position_hp[0];
00419 tmode3.ecefYOrLonHP = arp_position_hp[1];
00420 tmode3.ecefZOrAltHP = arp_position_hp[2];
00421
00422 tmode3.fixedPosAcc = (uint32_t)round(fixed_pos_acc * 1e4);
00423 return configure(tmode3);
00424 }
00425
00426 bool Gps::configTmode3SurveyIn(unsigned int svin_min_dur,
00427 float svin_acc_limit) {
00428 CfgTMODE3 tmode3;
00429 ROS_DEBUG("Setting TMODE3 to Survey In");
00430 tmode3.flags = tmode3.FLAGS_MODE_SURVEY_IN & tmode3.FLAGS_MODE_MASK;
00431 tmode3.svinMinDur = svin_min_dur;
00432
00433 tmode3.svinAccLimit = (int)round(svin_acc_limit * 1e4);
00434 return configure(tmode3);
00435 }
00436
00437 bool Gps::disableTmode3() {
00438 ROS_DEBUG("Disabling TMODE3");
00439
00440 CfgTMODE3 tmode3;
00441 tmode3.flags = tmode3.FLAGS_MODE_DISABLED & tmode3.FLAGS_MODE_MASK;
00442 return configure(tmode3);
00443 }
00444
00445 bool Gps::setRate(uint8_t class_id, uint8_t message_id, uint8_t rate) {
00446 ROS_DEBUG_COND(debug >= 2, "Setting rate 0x%02x, 0x%02x, %u", class_id,
00447 message_id, rate);
00448 ublox_msgs::CfgMSG msg;
00449 msg.msgClass = class_id;
00450 msg.msgID = message_id;
00451 msg.rate = rate;
00452 return configure(msg);
00453 }
00454
00455 bool Gps::setDynamicModel(uint8_t model) {
00456 ROS_DEBUG("Setting dynamic model to %u", model);
00457
00458 ublox_msgs::CfgNAV5 msg;
00459 msg.dynModel = model;
00460 msg.mask = ublox_msgs::CfgNAV5::MASK_DYN;
00461 return configure(msg);
00462 }
00463
00464 bool Gps::setFixMode(uint8_t mode) {
00465 ROS_DEBUG("Setting fix mode to %u", mode);
00466
00467 ublox_msgs::CfgNAV5 msg;
00468 msg.fixMode = mode;
00469 msg.mask = ublox_msgs::CfgNAV5::MASK_FIX_MODE;
00470 return configure(msg);
00471 }
00472
00473 bool Gps::setDeadReckonLimit(uint8_t limit) {
00474 ROS_DEBUG("Setting DR Limit to %u", limit);
00475
00476 ublox_msgs::CfgNAV5 msg;
00477 msg.drLimit = limit;
00478 msg.mask = ublox_msgs::CfgNAV5::MASK_DR_LIM;
00479 return configure(msg);
00480 }
00481
00482 bool Gps::setPpp(bool enable) {
00483 ROS_DEBUG("%s PPP", (enable ? "Enabling" : "Disabling"));
00484
00485 ublox_msgs::CfgNAVX5 msg;
00486 msg.usePPP = enable;
00487 msg.mask1 = ublox_msgs::CfgNAVX5::MASK1_PPP;
00488 return configure(msg);
00489 }
00490
00491 bool Gps::setDgnss(uint8_t mode) {
00492 CfgDGNSS cfg;
00493 ROS_DEBUG("Setting DGNSS mode to %u", mode);
00494 cfg.dgnssMode = mode;
00495 return configure(cfg);
00496 }
00497
00498 bool Gps::setUseAdr(bool enable) {
00499 ROS_DEBUG("%s ADR/UDR", (enable ? "Enabling" : "Disabling"));
00500
00501 ublox_msgs::CfgNAVX5 msg;
00502 msg.useAdr = enable;
00503 msg.mask2 = ublox_msgs::CfgNAVX5::MASK2_ADR;
00504 return configure(msg);
00505 }
00506
00507 bool Gps::poll(uint8_t class_id, uint8_t message_id,
00508 const std::vector<uint8_t>& payload) {
00509 if (!worker_) return false;
00510
00511 std::vector<unsigned char> out(kWriterSize);
00512 ublox::Writer writer(out.data(), out.size());
00513 if (!writer.write(payload.data(), payload.size(), class_id, message_id))
00514 return false;
00515 worker_->send(out.data(), writer.end() - out.data());
00516
00517 return true;
00518 }
00519
00520 bool Gps::waitForAcknowledge(const boost::posix_time::time_duration& timeout,
00521 uint8_t class_id, uint8_t msg_id) {
00522 ROS_DEBUG_COND(debug >= 2, "Waiting for ACK 0x%02x / 0x%02x",
00523 class_id, msg_id);
00524 boost::posix_time::ptime wait_until(
00525 boost::posix_time::second_clock::local_time() + timeout);
00526
00527 Ack ack = ack_.load(boost::memory_order_seq_cst);
00528 while (boost::posix_time::second_clock::local_time() < wait_until
00529 && (ack.class_id != class_id
00530 || ack.msg_id != msg_id
00531 || ack.type == WAIT)) {
00532 worker_->wait(timeout);
00533 ack = ack_.load(boost::memory_order_seq_cst);
00534 }
00535 bool result = ack.type == ACK
00536 && ack.class_id == class_id
00537 && ack.msg_id == msg_id;
00538 return result;
00539 }
00540 }