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
4 changes: 2 additions & 2 deletions ublox_gps/include/ublox_gps/ublox_firmware7.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,10 +26,10 @@ class UbloxFirmware7 final : public UbloxFirmware7Plus<ublox_msgs::msg::NavPVT7>
explicit UbloxFirmware7(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)
: UbloxFirmware7Plus<ublox_msgs::msg::NavPVT7>(frame_id, updater, freq_diag, gnss, node) {
if (getRosBoolean(node_, "publish.nav.svinfo")) {
nav_svinfo_pub_ = node->create_publisher<ublox_msgs::msg::NavSVINFO>("navsvinfo", 1);
nav_svinfo_pub_ = node->create_publisher<ublox_msgs::msg::NavSVINFO>("~/navsvinfo", 1);
}
if (getRosBoolean(node_, "publish.mon.hw")) {
mon_hw_pub_ = node->create_publisher<ublox_msgs::msg::MonHW>("monhw", 1);
mon_hw_pub_ = node->create_publisher<ublox_msgs::msg::MonHW>("~/monhw", 1);
}
}

Expand Down
6 changes: 3 additions & 3 deletions ublox_gps/include/ublox_gps/ublox_firmware8.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,13 +26,13 @@ class UbloxFirmware8 : public UbloxFirmware7Plus<ublox_msgs::msg::NavPVT> {
explicit UbloxFirmware8(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)
: UbloxFirmware7Plus<ublox_msgs::msg::NavPVT>(frame_id, updater, freq_diag, gnss, node) {
if (getRosBoolean(node_, "publish.nav.sat")) {
nav_sat_pub_ = node->create_publisher<ublox_msgs::msg::NavSAT>("navstate", 1);
nav_sat_pub_ = node->create_publisher<ublox_msgs::msg::NavSAT>("~/navstate", 1);
}
if (getRosBoolean(node_, "publish.mon.hw")) {
mon_hw_pub_ = node->create_publisher<ublox_msgs::msg::MonHW>("monhw", 1);
mon_hw_pub_ = node->create_publisher<ublox_msgs::msg::MonHW>("~/monhw", 1);
}
if (getRosBoolean(node_, "publish.rxm.rtcm")) {
rxm_rtcm_pub_ = node->create_publisher<ublox_msgs::msg::RxmRTCM>("rxmrtcm", 1);
rxm_rtcm_pub_ = node->create_publisher<ublox_msgs::msg::RxmRTCM>("~/rxmrtcm", 1);
}
}

Expand Down
16 changes: 8 additions & 8 deletions ublox_gps/src/adr_udr_product.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,26 +30,26 @@ AdrUdrProduct::AdrUdrProduct(float protocol_version, uint16_t nav_rate, uint16_t
{
if (getRosBoolean(node_, "publish.esf.meas")) {
imu_pub_ =
node_->create_publisher<sensor_msgs::msg::Imu>("imu_meas", 1);
node_->create_publisher<sensor_msgs::msg::Imu>("~/imu_meas", 1);
time_ref_pub_ =
node_->create_publisher<sensor_msgs::msg::TimeReference>("interrupt_time", 1);
node_->create_publisher<sensor_msgs::msg::TimeReference>("~/interrupt_time", 1);

esf_meas_pub_ = node_->create_publisher<ublox_msgs::msg::EsfMEAS>("esfmeas", 1);
esf_meas_pub_ = node_->create_publisher<ublox_msgs::msg::EsfMEAS>("~/esfmeas", 1);
}
if (getRosBoolean(node_, "publish.nav.att")) {
nav_att_pub_ = node_->create_publisher<ublox_msgs::msg::NavATT>("navatt", 1);
nav_att_pub_ = node_->create_publisher<ublox_msgs::msg::NavATT>("~/navatt", 1);
}
if (getRosBoolean(node_, "publish.esf.ins")) {
esf_ins_pub_ = node_->create_publisher<ublox_msgs::msg::EsfINS>("esfins", 1);
esf_ins_pub_ = node_->create_publisher<ublox_msgs::msg::EsfINS>("~/esfins", 1);
}
if (getRosBoolean(node_, "publish.esf.raw")) {
esf_raw_pub_ = node_->create_publisher<ublox_msgs::msg::EsfRAW>("esfraw", 1);
esf_raw_pub_ = node_->create_publisher<ublox_msgs::msg::EsfRAW>("~/esfraw", 1);
}
if (getRosBoolean(node_, "publish.esf.status")) {
esf_status_pub_ = node_->create_publisher<ublox_msgs::msg::EsfSTATUS>("esfstatus", 1);
esf_status_pub_ = node_->create_publisher<ublox_msgs::msg::EsfSTATUS>("~/esfstatus", 1);
}
if (getRosBoolean(node_, "publish.hnr.pvt")) {
hnr_pvt_pub_ = node_->create_publisher<ublox_msgs::msg::HnrPVT>("hnrpvt", 1);
hnr_pvt_pub_ = node_->create_publisher<ublox_msgs::msg::HnrPVT>("~/hnrpvt", 1);
}
}

Expand Down
4 changes: 2 additions & 2 deletions ublox_gps/src/hp_pos_rec_product.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,12 +25,12 @@ HpPosRecProduct::HpPosRecProduct(uint16_t nav_rate, uint16_t meas_rate, const st
{
if (getRosBoolean(node_, "publish.nav.relposned")) {
nav_relposned_pub_ =
node_->create_publisher<ublox_msgs::msg::NavRELPOSNED9>("navrelposned", 1);
node_->create_publisher<ublox_msgs::msg::NavRELPOSNED9>("~/navrelposned", 1);
}

if (getRosBoolean(node_, "publish.nav.heading")) {
imu_pub_ =
node_->create_publisher<sensor_msgs::msg::Imu>("navheading", 1);
node_->create_publisher<sensor_msgs::msg::Imu>("~/navheading", 1);
}
}

Expand Down
2 changes: 1 addition & 1 deletion ublox_gps/src/hpg_ref_product.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ HpgRefProduct::HpgRefProduct(uint16_t nav_rate, uint16_t meas_rate, std::shared_
{
if (getRosBoolean(node_, "publish.nav.svin")) {
navsvin_pub_ =
node_->create_publisher<ublox_msgs::msg::NavSVIN>("navsvin", 1);
node_->create_publisher<ublox_msgs::msg::NavSVIN>("~/navsvin", 1);
}
}

Expand Down
2 changes: 1 addition & 1 deletion ublox_gps/src/hpg_rov_product.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ HpgRovProduct::HpgRovProduct(uint16_t nav_rate, std::shared_ptr<diagnostic_updat
{
if (getRosBoolean(node_, "publish.nav.relposned")) {
nav_rel_pos_ned_pub_ =
node_->create_publisher<ublox_msgs::msg::NavRELPOSNED>("navrelposned", 1);
node_->create_publisher<ublox_msgs::msg::NavRELPOSNED>("~/navrelposned", 1);
}
}

Expand Down
18 changes: 9 additions & 9 deletions ublox_gps/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -475,33 +475,33 @@ void UbloxNode::getRosParams() {

// Create publishers based on parameters
if (getRosBoolean(this, "publish.nav.status")) {
nav_status_pub_ = this->create_publisher<ublox_msgs::msg::NavSTATUS>("navstatus", 1);
nav_status_pub_ = this->create_publisher<ublox_msgs::msg::NavSTATUS>("~/navstatus", 1);
}
if (getRosBoolean(this, "publish.nav.posecef")) {
nav_posecef_pub_ = this->create_publisher<ublox_msgs::msg::NavPOSECEF>("navposecef", 1);
nav_posecef_pub_ = this->create_publisher<ublox_msgs::msg::NavPOSECEF>("~/navposecef", 1);
}
if (getRosBoolean(this, "publish.nav.cov")) {
nav_cov_pub_ = this->create_publisher<ublox_msgs::msg::NavCOV>("navcov", 1);
nav_cov_pub_ = this->create_publisher<ublox_msgs::msg::NavCOV>("~/navcov", 1);
}
if (getRosBoolean(this, "publish.nav.clock")) {
nav_clock_pub_ = this->create_publisher<ublox_msgs::msg::NavCLOCK>("navclock", 1);
nav_clock_pub_ = this->create_publisher<ublox_msgs::msg::NavCLOCK>("~/navclock", 1);
}
if (getRosBoolean(this, "publish.aid.alm")) {
aid_alm_pub_ = this->create_publisher<ublox_msgs::msg::AidALM>("aidalm", 1);
aid_alm_pub_ = this->create_publisher<ublox_msgs::msg::AidALM>("~/aidalm", 1);
}
if (getRosBoolean(this, "publish.aid.eph")) {
aid_eph_pub_ = this->create_publisher<ublox_msgs::msg::AidEPH>("aideph", 1);
aid_eph_pub_ = this->create_publisher<ublox_msgs::msg::AidEPH>("~/aideph", 1);
}
if (getRosBoolean(this, "publish.aid.hui")) {
aid_hui_pub_ = this->create_publisher<ublox_msgs::msg::AidHUI>("aidhui", 1);
aid_hui_pub_ = this->create_publisher<ublox_msgs::msg::AidHUI>("~/aidhui", 1);
}
if (getRosBoolean(this, "publish.nmea")) {
// Larger queue depth to handle all NMEA strings being published consecutively
nmea_pub_ = this->create_publisher<nmea_msgs::msg::Sentence>("nmea", 20);
nmea_pub_ = this->create_publisher<nmea_msgs::msg::Sentence>("~/nmea", 20);
}

// 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));
this->subscription_ = this->create_subscription<rtcm_msgs::msg::Message>("~/rtcm", 10, std::bind(&UbloxNode::rtcmCallback, this, std::placeholders::_1));
}

void UbloxNode::keepAlive() {
Expand Down
4 changes: 2 additions & 2 deletions ublox_gps/src/raw_data_pa.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ RawDataStreamPa::RawDataStreamPa(bool is_ros_subscriber) : rclcpp::Node("raw_dat
flag_publish_(false),
is_ros_subscriber_(is_ros_subscriber) {

raw_pub_ = this->create_publisher<std_msgs::msg::UInt8MultiArray>("raw_data_stream", 100);
raw_pub_ = this->create_publisher<std_msgs::msg::UInt8MultiArray>("~/raw_data_stream", 100);

this->declare_parameter("dir", "");
this->declare_parameter("raw_data_stream.dir", "");
Expand Down Expand Up @@ -89,7 +89,7 @@ void RawDataStreamPa::initialize() {
if (is_ros_subscriber_) {
RCLCPP_INFO(this->get_logger(), "Subscribing to raw data stream.");
raw_data_stream_sub_ =
this->create_subscription<std_msgs::msg::UInt8MultiArray>("raw_data_stream", rclcpp::QoS(100),
this->create_subscription<std_msgs::msg::UInt8MultiArray>("~/raw_data_stream", rclcpp::QoS(100),
std::bind(&RawDataStreamPa::msgCallback, this, std::placeholders::_1));
} else if (flag_publish_) {
RCLCPP_INFO(this->get_logger(), "Publishing raw data stream.");
Expand Down
8 changes: 4 additions & 4 deletions ublox_gps/src/raw_data_product.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,16 +21,16 @@ namespace ublox_node {
RawDataProduct::RawDataProduct(uint16_t nav_rate, uint16_t meas_rate, std::shared_ptr<diagnostic_updater::Updater> updater, rclcpp::Node* node)
: nav_rate_(nav_rate), meas_rate_(meas_rate), updater_(updater), node_(node) {
if (getRosBoolean(node_, "publish.rxm.raw")) {
rxm_raw_pub_ = node_->create_publisher<ublox_msgs::msg::RxmRAW>("rxmraw", 1);
rxm_raw_pub_ = node_->create_publisher<ublox_msgs::msg::RxmRAW>("~/rxmraw", 1);
}
if (getRosBoolean(node_, "publish.rxm.sfrb")) {
rxm_sfrb_pub_ = node_->create_publisher<ublox_msgs::msg::RxmSFRB>("rxmsfrb", 1);
rxm_sfrb_pub_ = node_->create_publisher<ublox_msgs::msg::RxmSFRB>("~/rxmsfrb", 1);
}
if (getRosBoolean(node_, "publish.rxm.eph")) {
rxm_eph_pub_ = node_->create_publisher<ublox_msgs::msg::RxmEPH>("rxmeph", 1);
rxm_eph_pub_ = node_->create_publisher<ublox_msgs::msg::RxmEPH>("~/rxmeph", 1);
}
if (getRosBoolean(node_, "publish.rxm.almRaw")) {
rxm_alm_pub_ = node_->create_publisher<ublox_msgs::msg::RxmALM>("rxmalm", 1);
rxm_alm_pub_ = node_->create_publisher<ublox_msgs::msg::RxmALM>("~/rxmalm", 1);
}
}

Expand Down
8 changes: 4 additions & 4 deletions ublox_gps/src/tim_product.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,15 +23,15 @@ namespace ublox_node {
TimProduct::TimProduct(const std::string & frame_id, std::shared_ptr<diagnostic_updater::Updater> updater, rclcpp::Node* node) : frame_id_(frame_id), updater_(updater), node_(node)
{
timtm2_pub_ =
node_->create_publisher<ublox_msgs::msg::TimTM2>("timtm2", 1);
node_->create_publisher<ublox_msgs::msg::TimTM2>("~/timtm2", 1);
interrupt_time_pub_ =
node_->create_publisher<sensor_msgs::msg::TimeReference>("interrupt_time", 1);
node_->create_publisher<sensor_msgs::msg::TimeReference>("~/interrupt_time", 1);

if (getRosBoolean(node_, "publish.rxm.sfrb")) {
rxm_sfrb_pub_ = node_->create_publisher<ublox_msgs::msg::RxmSFRBX>("rxmsfrb", 1);
rxm_sfrb_pub_ = node_->create_publisher<ublox_msgs::msg::RxmSFRBX>("~/rxmsfrb", 1);
}
if (getRosBoolean(node_, "publish.rxm.raw")) {
rxm_raw_pub_ = node_->create_publisher<ublox_msgs::msg::RxmRAWX>("rxmraw", 1);
rxm_raw_pub_ = node_->create_publisher<ublox_msgs::msg::RxmRAWX>("~/rxmraw", 1);
}
}

Expand Down
10 changes: 5 additions & 5 deletions ublox_gps/src/ublox_firmware6.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,15 +32,15 @@ UbloxFirmware6::UbloxFirmware6(const std::string & frame_id, std::shared_ptr<dia
{
if (getRosBoolean(node_, "publish.nav.posllh")) {
nav_pos_llh_pub_ =
node_->create_publisher<ublox_msgs::msg::NavPOSLLH>("navposllh", 1);
node_->create_publisher<ublox_msgs::msg::NavPOSLLH>("~/navposllh", 1);
}

fix_pub_ =
node_->create_publisher<sensor_msgs::msg::NavSatFix>("~/fix", 1);

if (getRosBoolean(node_, "publish.nav.velned")) {
nav_vel_ned_pub_ =
node_->create_publisher<ublox_msgs::msg::NavVELNED>("navvelned", 1);
node_->create_publisher<ublox_msgs::msg::NavVELNED>("~/navvelned", 1);
}

vel_pub_ =
Expand All @@ -49,15 +49,15 @@ UbloxFirmware6::UbloxFirmware6(const std::string & frame_id, std::shared_ptr<dia

if (getRosBoolean(node_, "publish.nav.sol")) {
nav_sol_pub_ =
node_->create_publisher<ublox_msgs::msg::NavSOL>("navsol", 1);
node_->create_publisher<ublox_msgs::msg::NavSOL>("~/navsol", 1);
}
if (getRosBoolean(node_, "publish.nav.svinfo")) {
nav_svinfo_pub_ =
node_->create_publisher<ublox_msgs::msg::NavSVINFO>("navinfo", 1);
node_->create_publisher<ublox_msgs::msg::NavSVINFO>("~/navinfo", 1);
}
if (getRosBoolean(node_, "publish.mon.hw")) {
mon_hw_pub_ =
node_->create_publisher<ublox_msgs::msg::MonHW6>("monhw", 1);
node_->create_publisher<ublox_msgs::msg::MonHW6>("~/monhw", 1);
}
}

Expand Down
6 changes: 3 additions & 3 deletions ublox_gps/src/ublox_firmware9.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,11 +17,11 @@ UbloxFirmware9::UbloxFirmware9(const std::string & frame_id, std::shared_ptr<dia
{
if (getRosBoolean(node_, "publish.nav.timegps"))
{
nav_timegps_pub_ = node->create_publisher<ublox_msgs::msg::NavTIMEGPS>("navtimegps", 1);
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);
nav_timeutc_pub_ = node->create_publisher<ublox_msgs::msg::NavTIMEUTC>("~/navtimeutc", 1);
}
}

Expand Down Expand Up @@ -127,7 +127,7 @@ ublox_msgs::msg::CfgVALSETCfgdata UbloxFirmware9::generateSignalConfig(uint32_t
}

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

// Subscribe to NAV TIMEGPS messages
Expand Down