Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Publish current versions #252

Open
wants to merge 1 commit into
base: ros2
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 8 additions & 0 deletions ublox_gps/include/ublox_gps/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@
#include <ublox_msgs/msg/cfg_cfg.hpp>
#include <ublox_msgs/msg/cfg_dat.hpp>
#include <ublox_msgs/msg/inf.h>
#include <ublox_msgs/msg/versions.hpp>
#include <rtcm_msgs/msg/message.hpp>
#include <nmea_msgs/msg/sentence.hpp>
// Ublox GPS includes
Expand Down Expand Up @@ -217,6 +218,10 @@ class UbloxNode final : public rclcpp::Node {

//! Determined From Mon VER
float protocol_version_ = 0.0;
std::string hardware_version_ = "";
std::string software_version_ = "";
//! Determined From FWVER
std::string firmware_version_ = "";
// Variables set from parameter server
//! Device port
std::string device_;
Expand Down Expand Up @@ -271,9 +276,12 @@ class UbloxNode final : public rclcpp::Node {
rclcpp::Publisher<ublox_msgs::msg::AidEPH>::SharedPtr aid_eph_pub_;
rclcpp::Publisher<ublox_msgs::msg::AidHUI>::SharedPtr aid_hui_pub_;
rclcpp::Publisher<nmea_msgs::msg::Sentence>::SharedPtr nmea_pub_;
rclcpp::Publisher<ublox_msgs::msg::Versions>::SharedPtr versions_pub_;

void publish_nmea(const std::string & sentence, const std::string & topic);

void publishVersions();

//! Navigation rate in measurement cycles, see CfgRate.msg
uint16_t nav_rate_{0};

Expand Down
24 changes: 22 additions & 2 deletions ublox_gps/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -444,6 +444,7 @@ void UbloxNode::getRosParams() {
this->declare_parameter("publish.tim.tm2", false);

this->declare_parameter("publish.nmea", true);
this->declare_parameter("publish.versions", true);

// INF parameters
this->declare_parameter("inf.all", true);
Expand Down Expand Up @@ -497,6 +498,11 @@ void UbloxNode::getRosParams() {
// Larger queue depth to handle all NMEA strings being published consecutively
nmea_pub_ = this->create_publisher<nmea_msgs::msg::Sentence>("nmea", 20);
}
if (getRosBoolean(this, "publish.versions")) {
rclcpp::QoS qos(1);
qos.transient_local();
versions_pub_ = this->create_publisher<ublox_msgs::msg::Versions>("versions", qos);
}

// Create subscriber for RTCM correction data to enable RTK
this->subscription_ = this->create_subscription<rtcm_msgs::msg::Message>("/rtcm", 10, std::bind(&UbloxNode::rtcmCallback, this, std::placeholders::_1));
Expand Down Expand Up @@ -641,9 +647,11 @@ void UbloxNode::processMonVer() {
throw std::runtime_error("Failed to poll MonVER & set relevant settings");
}

software_version_ = std::string(monVer.sw_version.begin(), monVer.sw_version.end());
hardware_version_ = std::string(monVer.hw_version.begin(), monVer.hw_version.end());
RCLCPP_INFO(this->get_logger(), "%s, HW VER: %s",
std::string(monVer.sw_version.begin(), monVer.sw_version.end()).c_str(),
std::string(monVer.hw_version.begin(), monVer.hw_version.end()).c_str());
software_version_.c_str(),
hardware_version_.c_str());
// Convert extension to vector of strings
std::vector<std::string> extensions;
extensions.reserve(monVer.extension.size());
Expand Down Expand Up @@ -694,6 +702,8 @@ void UbloxNode::processMonVer() {
strs = stringSplit(extensions[i], "=");
if (strs.size() > 1) {
if (strs[0] == "FWVER") {
firmware_version_ = strs[1];
RCLCPP_INFO(this->get_logger(), "FWVER: %s", firmware_version_.c_str());
if (strs[1].length() > 8) {
addProductInterface(strs[1].substr(0, 3), strs[1].substr(8, 10));
} else {
Expand Down Expand Up @@ -729,6 +739,7 @@ void UbloxNode::processMonVer() {
}
}
}
publishVersions();
}

bool UbloxNode::configureUblox() {
Expand Down Expand Up @@ -925,6 +936,15 @@ void UbloxNode::initialize() {
}
}

void UbloxNode::publishVersions() {
ublox_msgs::msg::Versions msg;
msg.hardware_version = hardware_version_;
msg.software_version = software_version_;
msg.firmware_version = firmware_version_;
msg.protocol_version = std::to_string(protocol_version_);
versions_pub_->publish(msg);
}

void UbloxNode::shutdown() {
if (gps_->isInitialized()) {
gps_->close();
Expand Down
1 change: 1 addition & 0 deletions ublox_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -99,6 +99,7 @@ set(msg_files
"msg/TimTM2.msg"
"msg/UpdSOSAck.msg"
"msg/UpdSOS.msg"
"msg/Versions.msg"
)

rosidl_generate_interfaces(${PROJECT_NAME}
Expand Down
4 changes: 4 additions & 0 deletions ublox_msgs/msg/Versions.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
string software_version
string hardware_version
string firmware_version
string protocol_version