Skip to content
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
2 changes: 2 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -180,6 +180,8 @@ To publish a given u-blox message to a ROS topic, set the parameter shown below
* `publish/nav/status`: Topic `~navstatus`
* `publish/nav/svin`: Topic `~navsvin`. **HPG Reference Station Devices only**
* `publish/nav/svinfo`: Topic `~navsvinfo`
* `publish/nav/timegps`: Topic `~navtimegps`
* `publish/nav/timeutc`: Topic `~navtimeutc`
* `publish/nav/velned`: Topic `~navvelned`. **Firmware <= 6 only.** For firmware 7 and above, see NavPVT

### ESF messages
Expand Down
9 changes: 9 additions & 0 deletions ublox_gps/include/ublox_gps/ublox_firmware9.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,8 @@

#include <ublox_msgs/msg/cfg_valset.hpp>
#include <ublox_msgs/msg/cfg_valset_cfgdata.hpp>
#include <ublox_msgs/msg/nav_timegps.hpp>
#include <ublox_msgs/msg/nav_timeutc.hpp>

#include <ublox_gps/fix_diagnostic.hpp>
#include <ublox_gps/gnss.hpp>
Expand All @@ -34,13 +36,20 @@ class UbloxFirmware9 final : public UbloxFirmware8 {
*/
bool configureUblox(std::shared_ptr<ublox_gps::Gps> gps) override;

/**
* @brief Subscribe to NAV-TIMEUTC, NAV-TIMEGPS messages.
*/
void subscribe(std::shared_ptr<ublox_gps::Gps> gps) override;

private:
/**
* @brief Populate the CfgVALSETCfgData data type
*
* @details A helper function used to generate a configuration for a single signal.
*/
ublox_msgs::msg::CfgVALSETCfgdata generateSignalConfig(uint32_t signalID, bool enable);
rclcpp::Publisher<ublox_msgs::msg::NavTIMEGPS>::SharedPtr nav_timegps_pub_;
rclcpp::Publisher<ublox_msgs::msg::NavTIMEUTC>::SharedPtr nav_timeutc_pub_;
};

} // namespace ublox_node
Expand Down
2 changes: 2 additions & 0 deletions ublox_gps/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -424,6 +424,8 @@ void UbloxNode::getRosParams() {
this->declare_parameter("publish.nav.svin", getRosBoolean(this, "publish.nav.all"));
this->declare_parameter("publish.nav.svinfo", getRosBoolean(this, "publish.nav.all"));
this->declare_parameter("publish.nav.status", getRosBoolean(this, "publish.nav.all"));
this->declare_parameter("publish.nav.timegps", getRosBoolean(this, "publish.nav.all"));
this->declare_parameter("publish.nav.timeutc", getRosBoolean(this, "publish.nav.all"));
this->declare_parameter("publish.nav.velned", getRosBoolean(this, "publish.nav.all"));

this->declare_parameter("publish.rxm.all", getRosBoolean(this, "publish.all"));
Expand Down
25 changes: 25 additions & 0 deletions ublox_gps/src/ublox_firmware9.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,14 @@ namespace ublox_node {
UbloxFirmware9::UbloxFirmware9(const std::string & frame_id, std::shared_ptr<diagnostic_updater::Updater> updater, std::shared_ptr<FixDiagnostic> freq_diag, std::shared_ptr<Gnss> gnss, rclcpp::Node* node)
: UbloxFirmware8(frame_id, updater, freq_diag, gnss, node)
{
if (getRosBoolean(node_, "publish.nav.timegps"))
{
nav_timegps_pub_ = node->create_publisher<ublox_msgs::msg::NavTIMEGPS>("navtimegps", 1);
}
if (getRosBoolean(node_, "publish.nav.timeutc"))
{
nav_timeutc_pub_ = node->create_publisher<ublox_msgs::msg::NavTIMEUTC>("navtimeutc", 1);
}
}

bool UbloxFirmware9::configureUblox(std::shared_ptr<ublox_gps::Gps> gps)
Expand Down Expand Up @@ -118,5 +126,22 @@ ublox_msgs::msg::CfgVALSETCfgdata UbloxFirmware9::generateSignalConfig(uint32_t
return signalConfig;
}

void UbloxFirmware9::subscribe(std::shared_ptr<ublox_gps::Gps> gps)
{
UbloxFirmware8::subscribe(gps);

// Subscribe to NAV TIMEGPS messages
if (getRosBoolean(node_, "publish.nav.timegps")) {
gps->subscribe<ublox_msgs::msg::NavTIMEGPS>([this](const ublox_msgs::msg::NavTIMEGPS &m) {
nav_timegps_pub_->publish(m); }, 1);
}

// Subscribe to NAV TIMEUTC messages
if (getRosBoolean(node_, "publish.nav.timeutc")) {
gps->subscribe<ublox_msgs::msg::NavTIMEUTC>([this](const ublox_msgs::msg::NavTIMEUTC &m) {
nav_timeutc_pub_->publish(m); }, 1);
}
}


} // namespace ublox_node
38 changes: 38 additions & 0 deletions ublox_msgs/include/ublox_msgs/serialization.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -2529,6 +2529,44 @@ struct UbloxSerializer<ublox_msgs::msg::NavTIMEGPS_<ContainerAllocator> > {
stream.next(m.t_acc);
}
};

template <typename ContainerAllocator>
struct UbloxSerializer<ublox_msgs::msg::NavTIMEUTC_<ContainerAllocator> > {
inline static void read(const uint8_t *data, uint32_t count,
ublox_msgs::msg::NavTIMEUTC_<ContainerAllocator> & m) {
UbloxIStream stream(const_cast<uint8_t *>(data), count);
stream.next(m.i_tow);
stream.next(m.t_acc);
stream.next(m.nano);
stream.next(m.year);
stream.next(m.month);
stream.next(m.day);
stream.next(m.hour);
stream.next(m.min);
stream.next(m.sec);
stream.next(m.valid);
}

inline static uint32_t serializedLength(const ublox_msgs::msg::NavTIMEUTC_<ContainerAllocator> & m) {
(void)m;
return 20;
}

inline static void write(uint8_t *data, uint32_t size,
const ublox_msgs::msg::NavTIMEUTC_<ContainerAllocator> & m) {
UbloxOStream stream(data, size);
stream.next(m.i_tow);
stream.next(m.t_acc);
stream.next(m.nano);
stream.next(m.year);
stream.next(m.month);
stream.next(m.day);
stream.next(m.hour);
stream.next(m.min);
stream.next(m.sec);
stream.next(m.valid);
}
};

///
/// @brief Serializes the RxmALM message which has a repeated block.
Expand Down