Skip to content

Commit 594c999

Browse files
authored
Merge pull request #256 from Muhammad540/ros2
fixed CfgNAVX5 message generation for protocol version >= 18
2 parents 577ef65 + 83f26d5 commit 594c999

File tree

6 files changed

+21
-14
lines changed

6 files changed

+21
-14
lines changed

ublox_gps/config/neo_m8u_rover.yaml

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -11,15 +11,15 @@ ublox_gps_node:
1111

1212
device: /dev/ttyACM0
1313
frame_id: m8u
14-
rate: 4 # in Hz
14+
rate: 4.0 # in Hz
1515
nav_rate: 4 # [# of measurement cycles], recommended 1 Hz, may
1616
# be either 5 Hz (Dual constellation) or
1717
# 8 Hz (GPS only)
1818
dynamic_model: airborne2 # Airborne < 2G, 2D fix not supported (3D only),
1919
# Max Alt: 50km
2020
# Max Horizontal Velocity: 250 m/s,
2121
# Max Vertical Velocity: 100 m/s
22-
fix_mode: 3
22+
fix_mode: 3d
2323
enable_ppp: true
2424
dr_limit: 1
2525

ublox_gps/include/ublox_gps/adr_udr_product.hpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -28,7 +28,7 @@ namespace ublox_node {
2828
*/
2929
class AdrUdrProduct final : public virtual ComponentInterface {
3030
public:
31-
explicit AdrUdrProduct(uint16_t nav_rate, uint16_t meas_rate, const std::string & frame_id, std::shared_ptr<diagnostic_updater::Updater> updater, rclcpp::Node* node);
31+
explicit AdrUdrProduct(float protocol_version, uint16_t nav_rate, uint16_t meas_rate, const std::string & frame_id, std::shared_ptr<diagnostic_updater::Updater> updater, rclcpp::Node* node);
3232

3333
/**
3434
* @brief Get the ADR/UDR parameters.
@@ -64,6 +64,7 @@ class AdrUdrProduct final : public virtual ComponentInterface {
6464
private:
6565
//! Whether or not to enable dead reckoning
6666
bool use_adr_;
67+
float protocol_version_;
6768

6869
sensor_msgs::msg::Imu imu_;
6970
sensor_msgs::msg::TimeReference t_ref_;
@@ -89,4 +90,4 @@ class AdrUdrProduct final : public virtual ComponentInterface {
8990

9091
} // namespace ublox_node
9192

92-
#endif // UBLOX_GPS_ADR_UDR_PRODUCT_HPP
93+
#endif // UBLOX_GPS_ADR_UDR_PRODUCT_HPP

ublox_gps/include/ublox_gps/gps.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -300,7 +300,7 @@ class Gps final {
300300
* @note This is part of the expert settings. It is recommended you check
301301
* the ublox manual first.
302302
*/
303-
bool setPpp(bool enable);
303+
bool setPpp(bool enable, float protocol_version);
304304

305305
/**
306306
* @brief Set the DGNSS mode (see CfgDGNSS message for details).
@@ -314,7 +314,7 @@ class Gps final {
314314
* @param enable If true, enable ADR.
315315
* @return true on ACK, false on other conditions.
316316
*/
317-
bool setUseAdr(bool enable);
317+
bool setUseAdr(bool enable, float protocol_version);
318318

319319
/**
320320
* @brief Configure the U-Blox to UTC time

ublox_gps/src/adr_udr_product.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -25,8 +25,8 @@ namespace ublox_node {
2525
//
2626
// u-blox ADR devices, partially implemented
2727
//
28-
AdrUdrProduct::AdrUdrProduct(uint16_t nav_rate, uint16_t meas_rate, const std::string & frame_id, std::shared_ptr<diagnostic_updater::Updater> updater, rclcpp::Node* node)
29-
: use_adr_(false), nav_rate_(nav_rate), meas_rate_(meas_rate), frame_id_(frame_id), updater_(updater), node_(node)
28+
AdrUdrProduct::AdrUdrProduct(float protocol_version, uint16_t nav_rate, uint16_t meas_rate, const std::string & frame_id, std::shared_ptr<diagnostic_updater::Updater> updater, rclcpp::Node* node)
29+
: protocol_version_(protocol_version) ,use_adr_(false), nav_rate_(nav_rate), meas_rate_(meas_rate), frame_id_(frame_id), updater_(updater), node_(node)
3030
{
3131
if (getRosBoolean(node_, "publish.esf.meas")) {
3232
imu_pub_ =
@@ -63,7 +63,7 @@ void AdrUdrProduct::getRosParams() {
6363
}
6464

6565
bool AdrUdrProduct::configureUblox(std::shared_ptr<ublox_gps::Gps> gps) {
66-
if (!gps->setUseAdr(use_adr_)) {
66+
if (!gps->setUseAdr(use_adr_, protocol_version_)) {
6767
throw std::runtime_error(std::string("Failed to ")
6868
+ (use_adr_ ? "enable" : "disable") + "use_adr");
6969
}

ublox_gps/src/gps.cpp

Lines changed: 8 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -555,11 +555,14 @@ bool Gps::setDeadReckonLimit(uint8_t limit) {
555555
return configure(msg);
556556
}
557557

558-
bool Gps::setPpp(bool enable) {
558+
bool Gps::setPpp(bool enable, float protocol_version) {
559559
RCLCPP_DEBUG(logger_,"%s PPP", (enable ? "Enabling" : "Disabling"));
560560

561561
ublox_msgs::msg::CfgNAVX5 msg;
562562
msg.use_ppp = enable;
563+
if(protocol_version >= 18){
564+
msg.version = 2;
565+
}
563566
msg.mask1 = ublox_msgs::msg::CfgNAVX5::MASK1_PPP;
564567
return configure(msg);
565568
}
@@ -571,11 +574,14 @@ bool Gps::setDgnss(uint8_t mode) {
571574
return configure(cfg);
572575
}
573576

574-
bool Gps::setUseAdr(bool enable) {
577+
bool Gps::setUseAdr(bool enable, float protocol_version) {
575578
RCLCPP_DEBUG(logger_, "%s ADR/UDR", (enable ? "Enabling" : "Disabling"));
576579

577580
ublox_msgs::msg::CfgNAVX5 msg;
578581
msg.use_adr = enable;
582+
if(protocol_version >= 18){
583+
msg.version = 2;
584+
}
579585
msg.mask2 = ublox_msgs::msg::CfgNAVX5::MASK2_ADR;
580586
return configure(msg);
581587
}

ublox_gps/src/node.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -229,11 +229,11 @@ void UbloxNode::addProductInterface(const std::string & product_category,
229229
components_.push_back(std::make_shared<TimProduct>(frame_id_, updater_, this));
230230
} else if (product_category == "ADR" ||
231231
product_category == "UDR") {
232-
components_.push_back(std::make_shared<AdrUdrProduct>(nav_rate_, meas_rate_, frame_id_, updater_, this));
232+
components_.push_back(std::make_shared<AdrUdrProduct>(protocol_version_, nav_rate_, meas_rate_, frame_id_, updater_, this));
233233
} else if (product_category == "FTS") {
234234
components_.push_back(std::make_shared<FtsProduct>());
235235
} else if (product_category == "HPS") {
236-
components_.push_back(std::make_shared<AdrUdrProduct>(nav_rate_, meas_rate_, frame_id_, updater_, this));
236+
components_.push_back(std::make_shared<AdrUdrProduct>(protocol_version_, nav_rate_, meas_rate_, frame_id_, updater_, this));
237237
components_.push_back(std::make_shared<HpgRovProduct>(nav_rate_, updater_, this));
238238
} else {
239239
RCLCPP_WARN(this->get_logger(), "Product category %s %s from MonVER message not recognized %s",
@@ -772,7 +772,7 @@ bool UbloxNode::configureUblox() {
772772
" SBAS.");
773773
}
774774
}
775-
if (!gps_->setPpp(getRosBoolean(this, "enable_ppp"))) {
775+
if (!gps_->setPpp(getRosBoolean(this, "enable_ppp"), protocol_version_)) {
776776
throw std::runtime_error(std::string("Failed to ") +
777777
(getRosBoolean(this, "enable_ppp") ? "enable" : "disable")
778778
+ " PPP.");

0 commit comments

Comments
 (0)