31 #include <boost/version.hpp>
41 boost::posix_time::milliseconds(
66 subscribe<ublox_msgs::UpdSOS_Ack>(
77 ack_.store(ack, boost::memory_order_seq_cst);
89 ack_.store(ack, boost::memory_order_seq_cst);
90 ROS_ERROR(
"U-blox: received NACK: 0x%02x / 0x%02x", m.clsID, m.msgID);
94 if (m.cmd == UpdSOS_Ack::CMD_BACKUP_CREATE_ACK) {
96 ack.
type = (m.response == m.BACKUP_CREATE_ACK) ?
ACK :
NACK;
100 ack_.store(ack, boost::memory_order_seq_cst);
102 "U-blox: received UPD SOS Backup ACK");
104 ROS_ERROR(
"U-blox: received UPD SOS Backup NACK");
109 uint16_t uart_in, uint16_t uart_out) {
112 new boost::asio::io_service);
114 new boost::asio::serial_port(*io_service));
119 }
catch (std::runtime_error& e) {
120 throw std::runtime_error(
"U-Blox: Could not open serial port :"
121 + port +
" " + e.what());
124 ROS_INFO(
"U-Blox: Opened serial port %s", port.c_str());
126 if(BOOST_VERSION < 106600)
131 int fd = serial->native_handle();
135 tcsetattr(fd, TCSANOW, &tio);
146 boost::asio::serial_port_base::baud_rate current_baudrate;
147 serial->get_option(current_baudrate);
150 if (current_baudrate.value() == baudrate)
156 boost::asio::serial_port_base::baud_rate(
kBaudrates[i]));
157 boost::this_thread::sleep(
159 serial->get_option(current_baudrate);
160 ROS_DEBUG(
"U-Blox: Set ASIO baudrate to %u", current_baudrate.value());
164 if(!
configured_ || current_baudrate.value() != baudrate) {
165 throw std::runtime_error(
"Could not configure serial baud rate");
174 new boost::asio::io_service);
176 new boost::asio::serial_port(*io_service));
181 }
catch (std::runtime_error& e) {
182 throw std::runtime_error(
"U-Blox: Could not open serial port :"
183 + port +
" " + e.what());
186 ROS_INFO(
"U-Blox: Reset serial port %s", port.c_str());
195 std::vector<uint8_t> payload;
196 payload.push_back(CfgPRT::PORT_ID_UART1);
197 if (!
poll(CfgPRT::CLASS_ID, CfgPRT::MESSAGE_ID, payload)) {
198 ROS_ERROR(
"Resetting Serial Port: Could not poll UART1 CfgPRT");
203 ROS_ERROR(
"Resetting Serial Port: Could not read polled UART1 CfgPRT %s",
209 serial->set_option(boost::asio::serial_port_base::baud_rate(prt.baudRate));
217 new boost::asio::io_service);
218 boost::asio::ip::tcp::resolver::iterator endpoint;
221 boost::asio::ip::tcp::resolver resolver(*io_service);
223 resolver.resolve(boost::asio::ip::tcp::resolver::query(host, port));
224 }
catch (std::runtime_error& e) {
225 throw std::runtime_error(
"U-Blox: Could not resolve" + host +
" " +
226 port +
" " + e.what());
230 new boost::asio::ip::tcp::socket(*io_service));
233 socket->connect(*endpoint);
234 }
catch (std::runtime_error& e) {
235 throw std::runtime_error(
"U-Blox: Could not connect to " +
236 endpoint->host_name() +
":" +
237 endpoint->service_name() +
": " + e.what());
240 ROS_INFO(
"U-Blox: Connected to %s:%s.", endpoint->host_name().c_str(),
241 endpoint->service_name().c_str());
253 new boost::asio::io_service);
254 boost::asio::ip::udp::resolver::iterator endpoint;
257 boost::asio::ip::udp::resolver resolver(*io_service);
259 resolver.resolve(boost::asio::ip::udp::resolver::query(host, port));
260 }
catch (std::runtime_error& e) {
261 throw std::runtime_error(
"U-Blox: Could not resolve" + host +
" " +
262 port +
" " + e.what());
266 new boost::asio::ip::udp::socket(*io_service));
269 socket->connect(*endpoint);
270 }
catch (std::runtime_error& e) {
271 throw std::runtime_error(
"U-Blox: Could not connect to " +
272 endpoint->host_name() +
":" +
273 endpoint->service_name() +
": " + e.what());
276 ROS_INFO(
"U-Blox: Connected to %s:%s.", endpoint->host_name().c_str(),
277 endpoint->service_name().c_str());
290 ROS_INFO(
"U-Blox Flash BBR failed to save");
296 void Gps::reset(
const boost::posix_time::time_duration& wait) {
300 boost::this_thread::sleep(
wait);
308 ROS_WARN(
"Resetting u-blox. If device address changes, %s",
309 "node must be relaunched.");
312 rst.navBbrMask = nav_bbr_mask;
313 rst.resetMode = reset_mode;
322 const boost::posix_time::time_duration& wait) {
328 ROS_WARN(
"GNSS re-configured, cold resetting device.");
329 if (!
configReset(CfgRST::NAV_BBR_COLD_START, CfgRST::RESET_MODE_GNSS))
340 rst.navBbrMask = rst.NAV_BBR_HOT_START;
341 rst.resetMode = rst.RESET_MODE_GNSS_STOP;
354 sos.cmd = sos.CMD_FLASH_BACKUP_CLEAR;
359 uint16_t out_proto_mask) {
362 ROS_DEBUG(
"Configuring UART1 baud rate: %u, In/Out Protocol: %u / %u",
363 baudrate, in_proto_mask, out_proto_mask);
366 port.portID = CfgPRT::PORT_ID_UART1;
367 port.baudRate = baudrate;
368 port.mode = CfgPRT::MODE_RESERVED1 | CfgPRT::MODE_CHAR_LEN_8BIT |
369 CfgPRT::MODE_PARITY_NO | CfgPRT::MODE_STOP_BITS_1;
370 port.inProtoMask = in_proto_mask;
371 port.outProtoMask = out_proto_mask;
379 std::vector<uint8_t> payload;
380 payload.push_back(CfgPRT::PORT_ID_UART1);
381 if (!
poll(CfgPRT::CLASS_ID, CfgPRT::MESSAGE_ID, payload)) {
382 ROS_ERROR(
"disableUart: Could not poll UART1 CfgPRT");
386 ROS_ERROR(
"disableUart: Could not read polled UART1 CfgPRT message");
391 port.portID = CfgPRT::PORT_ID_UART1;
392 port.mode = prev_config.mode;
393 port.baudRate = prev_config.baudRate;
394 port.inProtoMask = 0;
395 port.outProtoMask = 0;
396 port.txReady = prev_config.txReady;
397 port.flags = prev_config.flags;
402 uint16_t in_proto_mask,
403 uint16_t out_proto_mask) {
406 ROS_DEBUG(
"Configuring USB tx_ready: %u, In/Out Protocol: %u / %u",
407 tx_ready, in_proto_mask, out_proto_mask);
410 port.portID = CfgPRT::PORT_ID_USB;
411 port.txReady = tx_ready;
412 port.inProtoMask = in_proto_mask;
413 port.outProtoMask = out_proto_mask;
418 ROS_DEBUG(
"Configuring measurement rate to %u ms and nav rate to %u cycles",
424 rate.timeRef = CfgRATE::TIME_REF_GPS;
429 for(
size_t i = 0; i < ids.size(); ++i) {
430 ROS_DEBUG(
"Setting RTCM %d Rate %u", ids[i], rates[i]);
432 ROS_ERROR(
"Could not set RTCM %d to rate %u", ids[i], rates[i]);
440 ROS_DEBUG(
"Configuring SBAS: usage %u, max_sbas %u",
usage, max_sbas);
442 ublox_msgs::CfgSBAS
msg;
443 msg.mode = (enable ? CfgSBAS::MODE_ENABLED : 0);
445 msg.maxSBAS = max_sbas;
450 std::vector<float> arp_position,
451 std::vector<int8_t> arp_position_hp,
452 float fixed_pos_acc) {
453 if(arp_position.size() != 3 || arp_position_hp.size() != 3) {
454 ROS_ERROR(
"Configuring TMODE3 to Fixed: size of position %s",
455 "& arp_position_hp args must be 3");
459 ROS_DEBUG(
"Configuring TMODE3 to Fixed");
462 tmode3.flags = tmode3.FLAGS_MODE_FIXED & tmode3.FLAGS_MODE_MASK;
463 tmode3.flags |= lla_flag ? tmode3.FLAGS_LLA : 0;
468 tmode3.ecefXOrLat = (int)round(arp_position[0] * 1e7);
469 tmode3.ecefYOrLon = (int)round(arp_position[1] * 1e7);
470 tmode3.ecefZOrAlt = (int)round(arp_position[2] * 1e7);
473 tmode3.ecefXOrLat = (int)round(arp_position[0] * 1e2);
474 tmode3.ecefYOrLon = (int)round(arp_position[1] * 1e2);
475 tmode3.ecefZOrAlt = (int)round(arp_position[2] * 1e2);
477 tmode3.ecefXOrLatHP = arp_position_hp[0];
478 tmode3.ecefYOrLonHP = arp_position_hp[1];
479 tmode3.ecefZOrAltHP = arp_position_hp[2];
481 tmode3.fixedPosAcc = (uint32_t)round(fixed_pos_acc * 1e4);
486 float svin_acc_limit) {
488 ROS_DEBUG(
"Setting TMODE3 to Survey In");
489 tmode3.flags = tmode3.FLAGS_MODE_SURVEY_IN & tmode3.FLAGS_MODE_MASK;
490 tmode3.svinMinDur = svin_min_dur;
492 tmode3.svinAccLimit = (int)round(svin_acc_limit * 1e4);
500 tmode3.flags = tmode3.FLAGS_MODE_DISABLED & tmode3.FLAGS_MODE_MASK;
504 bool Gps::setRate(uint8_t class_id, uint8_t message_id, uint8_t rate) {
507 ublox_msgs::CfgMSG
msg;
508 msg.msgClass = class_id;
509 msg.msgID = message_id;
515 ROS_DEBUG(
"Setting dynamic model to %u", model);
517 ublox_msgs::CfgNAV5
msg;
518 msg.dynModel = model;
519 msg.mask = ublox_msgs::CfgNAV5::MASK_DYN;
524 ROS_DEBUG(
"Setting fix mode to %u", mode);
526 ublox_msgs::CfgNAV5
msg;
528 msg.mask = ublox_msgs::CfgNAV5::MASK_FIX_MODE;
533 ROS_DEBUG(
"Setting DR Limit to %u", limit);
535 ublox_msgs::CfgNAV5
msg;
537 msg.mask = ublox_msgs::CfgNAV5::MASK_DR_LIM;
542 ROS_DEBUG(
"%s PPP", (enable ?
"Enabling" :
"Disabling"));
544 ublox_msgs::CfgNAVX5
msg;
546 if(protocol_version >= 18)
548 msg.mask1 = ublox_msgs::CfgNAVX5::MASK1_PPP;
554 ROS_DEBUG(
"Setting DGNSS mode to %u", mode);
555 cfg.dgnssMode = mode;
560 ROS_DEBUG(
"%s ADR/UDR", (enable ?
"Enabling" :
"Disabling"));
562 ublox_msgs::CfgNAVX5
msg;
565 if(protocol_version >= 18)
567 msg.mask2 = ublox_msgs::CfgNAVX5::MASK2_ADR;
572 worker_->send(rtcm.data(), rtcm.size());
577 const std::vector<uint8_t>& payload) {
582 if (!writer.
write(payload.data(), payload.size(), class_id, message_id))
584 worker_->send(out.data(), writer.
end() - out.data());
590 uint8_t class_id, uint8_t msg_id) {
593 boost::posix_time::ptime wait_until(
594 boost::posix_time::second_clock::local_time() + timeout);
596 Ack ack =
ack_.load(boost::memory_order_seq_cst);
597 while (boost::posix_time::second_clock::local_time() < wait_until
602 ack =
ack_.load(boost::memory_order_seq_cst);
612 worker_->setRawDataCallback(callback);
618 ublox_msgs::CfgNAV5
msg;
624 ROS_DEBUG(
"TIM-TM2 send rate on current port set to %u", rate );
625 ublox_msgs::CfgMSG
msg;
626 msg.msgClass = ublox_msgs::TimTM2::CLASS_ID;
627 msg.msgID = ublox_msgs::TimTM2::MESSAGE_ID;