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(
158 boost::posix_time::milliseconds(kSetBaudrateSleepMs));
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());
254 ROS_INFO(
"U-Blox Flash BBR failed to save");
260 void Gps::reset(
const boost::posix_time::time_duration& wait) {
264 boost::this_thread::sleep(wait);
272 ROS_WARN(
"Resetting u-blox. If device address changes, %s",
273 "node must be relaunched.");
276 rst.navBbrMask = nav_bbr_mask;
277 rst.resetMode = reset_mode;
286 const boost::posix_time::time_duration& wait) {
292 ROS_WARN(
"GNSS re-configured, cold resetting device.");
293 if (!
configReset(CfgRST::NAV_BBR_COLD_START, CfgRST::RESET_MODE_GNSS))
304 rst.navBbrMask = rst.NAV_BBR_HOT_START;
305 rst.resetMode = rst.RESET_MODE_GNSS_STOP;
318 sos.cmd = sos.CMD_FLASH_BACKUP_CLEAR;
323 uint16_t out_proto_mask) {
326 ROS_DEBUG(
"Configuring UART1 baud rate: %u, In/Out Protocol: %u / %u",
327 baudrate, in_proto_mask, out_proto_mask);
330 port.portID = CfgPRT::PORT_ID_UART1;
331 port.baudRate = baudrate;
332 port.mode = CfgPRT::MODE_RESERVED1 | CfgPRT::MODE_CHAR_LEN_8BIT |
333 CfgPRT::MODE_PARITY_NO | CfgPRT::MODE_STOP_BITS_1;
334 port.inProtoMask = in_proto_mask;
335 port.outProtoMask = out_proto_mask;
343 std::vector<uint8_t> payload;
344 payload.push_back(CfgPRT::PORT_ID_UART1);
345 if (!
poll(CfgPRT::CLASS_ID, CfgPRT::MESSAGE_ID, payload)) {
346 ROS_ERROR(
"disableUart: Could not poll UART1 CfgPRT");
350 ROS_ERROR(
"disableUart: Could not read polled UART1 CfgPRT message");
355 port.portID = CfgPRT::PORT_ID_UART1;
356 port.mode = prev_config.mode;
357 port.baudRate = prev_config.baudRate;
358 port.inProtoMask = 0;
359 port.outProtoMask = 0;
360 port.txReady = prev_config.txReady;
361 port.flags = prev_config.flags;
366 uint16_t in_proto_mask,
367 uint16_t out_proto_mask) {
370 ROS_DEBUG(
"Configuring USB tx_ready: %u, In/Out Protocol: %u / %u",
371 tx_ready, in_proto_mask, out_proto_mask);
374 port.portID = CfgPRT::PORT_ID_USB;
375 port.txReady = tx_ready;
376 port.inProtoMask = in_proto_mask;
377 port.outProtoMask = out_proto_mask;
382 ROS_DEBUG(
"Configuring measurement rate to %u ms and nav rate to %u cycles",
383 meas_rate, nav_rate);
388 rate.timeRef = CfgRATE::TIME_REF_GPS;
393 for(
size_t i = 0; i < ids.size(); ++i) {
394 ROS_DEBUG(
"Setting RTCM %d Rate %u", ids[i], rates[i]);
396 ROS_ERROR(
"Could not set RTCM %d to rate %u", ids[i], rates[i]);
404 ROS_DEBUG(
"Configuring SBAS: usage %u, max_sbas %u", usage, max_sbas);
406 ublox_msgs::CfgSBAS
msg;
407 msg.mode = (enable ? CfgSBAS::MODE_ENABLED : 0);
409 msg.maxSBAS = max_sbas;
414 std::vector<float> arp_position,
415 std::vector<int8_t> arp_position_hp,
416 float fixed_pos_acc) {
417 if(arp_position.size() != 3 || arp_position_hp.size() != 3) {
418 ROS_ERROR(
"Configuring TMODE3 to Fixed: size of position %s",
419 "& arp_position_hp args must be 3");
423 ROS_DEBUG(
"Configuring TMODE3 to Fixed");
426 tmode3.flags = tmode3.FLAGS_MODE_FIXED & tmode3.FLAGS_MODE_MASK;
427 tmode3.flags |= lla_flag ? tmode3.FLAGS_LLA : 0;
432 tmode3.ecefXOrLat = (int)round(arp_position[0] * 1e7);
433 tmode3.ecefYOrLon = (int)round(arp_position[1] * 1e7);
434 tmode3.ecefZOrAlt = (int)round(arp_position[2] * 1e7);
437 tmode3.ecefXOrLat = (int)round(arp_position[0] * 1e2);
438 tmode3.ecefYOrLon = (int)round(arp_position[1] * 1e2);
439 tmode3.ecefZOrAlt = (int)round(arp_position[2] * 1e2);
441 tmode3.ecefXOrLatHP = arp_position_hp[0];
442 tmode3.ecefYOrLonHP = arp_position_hp[1];
443 tmode3.ecefZOrAltHP = arp_position_hp[2];
445 tmode3.fixedPosAcc = (uint32_t)round(fixed_pos_acc * 1e4);
450 float svin_acc_limit) {
452 ROS_DEBUG(
"Setting TMODE3 to Survey In");
453 tmode3.flags = tmode3.FLAGS_MODE_SURVEY_IN & tmode3.FLAGS_MODE_MASK;
454 tmode3.svinMinDur = svin_min_dur;
456 tmode3.svinAccLimit = (int)round(svin_acc_limit * 1e4);
464 tmode3.flags = tmode3.FLAGS_MODE_DISABLED & tmode3.FLAGS_MODE_MASK;
468 bool Gps::setRate(uint8_t class_id, uint8_t message_id, uint8_t rate) {
471 ublox_msgs::CfgMSG
msg;
472 msg.msgClass = class_id;
473 msg.msgID = message_id;
479 ROS_DEBUG(
"Setting dynamic model to %u", model);
481 ublox_msgs::CfgNAV5
msg;
482 msg.dynModel = model;
483 msg.mask = ublox_msgs::CfgNAV5::MASK_DYN;
488 ROS_DEBUG(
"Setting fix mode to %u", mode);
490 ublox_msgs::CfgNAV5
msg;
492 msg.mask = ublox_msgs::CfgNAV5::MASK_FIX_MODE;
497 ROS_DEBUG(
"Setting DR Limit to %u", limit);
499 ublox_msgs::CfgNAV5
msg;
501 msg.mask = ublox_msgs::CfgNAV5::MASK_DR_LIM;
506 ROS_DEBUG(
"%s PPP", (enable ?
"Enabling" :
"Disabling"));
508 ublox_msgs::CfgNAVX5
msg;
510 if(protocol_version >= 18)
512 msg.mask1 = ublox_msgs::CfgNAVX5::MASK1_PPP;
518 ROS_DEBUG(
"Setting DGNSS mode to %u", mode);
519 cfg.dgnssMode = mode;
524 ROS_DEBUG(
"%s ADR/UDR", (enable ?
"Enabling" :
"Disabling"));
526 ublox_msgs::CfgNAVX5
msg;
529 if(protocol_version >= 18)
531 msg.mask2 = ublox_msgs::CfgNAVX5::MASK2_ADR;
536 const std::vector<uint8_t>& payload) {
541 if (!writer.write(payload.data(), payload.size(), class_id, message_id))
543 worker_->send(out.data(), writer.end() - out.data());
549 uint8_t class_id, uint8_t msg_id) {
552 boost::posix_time::ptime wait_until(
553 boost::posix_time::second_clock::local_time() + timeout);
555 Ack ack =
ack_.load(boost::memory_order_seq_cst);
556 while (boost::posix_time::second_clock::local_time() < wait_until
561 ack =
ack_.load(boost::memory_order_seq_cst);
571 worker_->setRawDataCallback(callback);
577 ublox_msgs::CfgNAV5
msg;
583 ROS_DEBUG(
"TIM-TM2 send rate on current port set to %u", rate );
584 ublox_msgs::CfgMSG
msg;
585 msg.msgClass = ublox_msgs::TimTM2::CLASS_ID;
586 msg.msgID = ublox_msgs::TimTM2::MESSAGE_ID;
int debug
Used to determine which debug messages to display.
bool isConfigured() const
bool configGnss(ublox_msgs::CfgGNSS gnss, const boost::posix_time::time_duration &wait)
Configure the GNSS, cold reset the device, and reset the I/O.
void close()
Closes the I/O port, and initiates save on shutdown procedure if enabled.
bool poll(ConfigT &message, const std::vector< uint8_t > &payload=std::vector< uint8_t >(), const boost::posix_time::time_duration &timeout=default_timeout_)
boost::atomic< Ack > ack_
Stores last received ACK accessed by multiple threads.
bool configTmode3Fixed(bool lla_flag, std::vector< float > arp_position, std::vector< int8_t > arp_position_hp, float fixed_pos_acc)
Set the TMODE3 settings to fixed.
static constexpr int kSetBaudrateSleepMs
Sleep time [ms] after setting the baudrate.
bool save_on_shutdown_
Whether or not to save Flash BBR on shutdown.
void processNack(const ublox_msgs::Ack &m)
Callback handler for UBX-NACK message.
bool configReset(uint16_t nav_bbr_mask, uint16_t reset_mode)
Send a reset message to the u-blox device.
bool read(T &message, const boost::posix_time::time_duration &timeout=default_timeout_)
bool disableUart1(ublox_msgs::CfgPRT &prev_cfg)
Disable the UART Port. Sets in/out protocol masks to 0. Does not modify other values.
uint8_t class_id
The class ID of the ACK.
bool setUseAdr(bool enable, float protocol_version)
Enable or disable ADR (automotive dead reckoning).
bool setFixMode(uint8_t mode)
Set the device fix mode.
bool configRate(uint16_t meas_rate, uint16_t nav_rate)
Configure the device navigation and measurement rate settings.
bool configSbas(bool enable, uint8_t usage, uint8_t max_sbas)
Configure the SBAS settings.
static constexpr unsigned int kBaudrates[]
Possible baudrates for u-blox devices.
void setWorker(const boost::shared_ptr< Worker > &worker)
Set the I/O worker.
bool setTimtm2(uint8_t rate)
Enable or disable TIM-TM2 (time mark message).
uint16_t nav_rate
Navigation rate in measurement cycles, see CfgRate.msg.
Stores ACK/NACK messages.
bool disableTmode3()
Set the TMODE3 settings to disabled. Should only be called for High Precision GNSS devices...
boost::function< void(unsigned char *, std::size_t &)> Callback
bool configTmode3SurveyIn(unsigned int svin_min_dur, float svin_acc_limit)
Set the TMODE3 settings to survey-in.
bool waitForAcknowledge(const boost::posix_time::time_duration &timeout, uint8_t class_id, uint8_t msg_id)
Wait for an acknowledge message until the timeout.
void reset(const boost::posix_time::time_duration &wait)
Reset I/O communications.
void initializeSerial(std::string port, unsigned int baudrate, uint16_t uart_in, uint16_t uart_out)
Initialize the Serial I/O port.
bool configUart1(unsigned int baudrate, uint16_t in_proto_mask, uint16_t out_proto_mask)
Configure the UART1 Port.
bool config_on_startup_flag_
Flag for enabling configuration on startup.
bool configured_
Whether or not the I/O port has been configured.
static const uint8_t NACK
bool config_on_startup_flag_
CallbackHandlers callbacks_
Callback handlers for u-blox messages.
uint8_t msg_id
The message ID of the ACK.
bool setRate(uint8_t class_id, uint8_t message_id, uint8_t rate)
Set the rate at which the U-Blox device sends the given message.
void setRawDataCallback(const Worker::Callback &callback)
Set the callback function which handles raw data.
AckType type
The ACK type.
bool setDgnss(uint8_t mode)
Set the DGNSS mode (see CfgDGNSS message for details).
static constexpr double kDefaultAckTimeout
Default timeout for ACK messages in seconds.
void readCallback(unsigned char *data, std::size_t &size)
Processes u-blox messages in the given buffer & clears the read messages from the buffer...
bool setPpp(bool enable, float protocol_version)
Enable or disable PPP (precise-point-positioning).
bool configUsb(uint16_t tx_ready, uint16_t in_proto_mask, uint16_t out_proto_mask)
Configure the USB Port.
static constexpr int kWriterSize
Size of write buffer for output messages.
void resetSerial(std::string port)
Reset the Serial I/O port after u-blox reset.
void subscribeAcks()
Subscribe to ACK/NACK messages and UPD-SOS-ACK messages.
uint16_t meas_rate
The measurement [ms], see CfgRate.msg.
void processAck(const ublox_msgs::Ack &m)
Callback handler for UBX-ACK message.
bool setDeadReckonLimit(uint8_t limit)
Set the dead reckoning time limit.
Handles Asynchronous I/O reading and writing.
#define ROS_DEBUG_COND(cond,...)
void processUpdSosAck(const ublox_msgs::UpdSOS_Ack &m)
Callback handler for UBX-UPD-SOS-ACK message.
static const uint8_t RTCM
static const boost::posix_time::time_duration default_timeout_
The default timeout for ACK messages.
boost::shared_ptr< Worker > worker_
Processes I/O stream data.
bool saveOnShutdown()
Execute save on shutdown procedure.
bool configRtcm(std::vector< uint8_t > ids, std::vector< uint8_t > rates)
Configure the RTCM messages with the given IDs to the set rate.
bool configure(const ConfigT &message, bool wait=true)
Send the given configuration message.
bool setDynamicModel(uint8_t model)
Set the device dynamic model.
bool clearBbr()
Send a message to the receiver to delete the BBR data stored in flash.
void initializeTcp(std::string host, std::string port)
Initialize TCP I/O.
bool setUTCtime()
Configure the U-Blox to UTC time.