Skip to content

Commit 24c4722

Browse files
authored
Fix parameter declaration types. (#146)
Instead of trying to force things with template arguments, instead explicitly declare the type when declaring arguments without a default. This should allow the types to be properly set while still allowing these to be run without a parameter explicitly set. Signed-off-by: Chris Lalancette <[email protected]>
1 parent daaa065 commit 24c4722

File tree

1 file changed

+13
-13
lines changed

1 file changed

+13
-13
lines changed

ublox_gps/src/node.cpp

Lines changed: 13 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -250,8 +250,8 @@ void UbloxNode::getRosParams() {
250250
uart_out_ = declareRosIntParameter<uint16_t>(this, "uart1.out", ublox_msgs::msg::CfgPRT::PROTO_UBX);
251251
// USB params
252252
set_usb_ = false;
253-
this->declare_parameter<int64_t>("usb.in");
254-
this->declare_parameter<int64_t>("usb.out");
253+
this->declare_parameter("usb.in", rclcpp::PARAMETER_INTEGER);
254+
this->declare_parameter("usb.out", rclcpp::PARAMETER_INTEGER);
255255
usb_tx_ = declareRosIntParameter<uint16_t>(this, "usb.tx_ready", 0);
256256
if (isRosParameterSet(this, "usb.in") || isRosParameterSet(this, "usb.out")) {
257257
set_usb_ = true;
@@ -271,8 +271,8 @@ void UbloxNode::getRosParams() {
271271
nav_rate_ = declareRosIntParameter<uint16_t>(this, "nav_rate", 1); // # of measurement rate cycles
272272

273273
// RTCM params
274-
this->declare_parameter<std::vector<int64_t>>("rtcm.ids");
275-
this->declare_parameter<std::vector<int64_t>>("rtcm.rates");
274+
this->declare_parameter("rtcm.ids", rclcpp::PARAMETER_INTEGER_ARRAY);
275+
this->declare_parameter("rtcm.rates", rclcpp::PARAMETER_INTEGER_ARRAY);
276276
std::vector<int64_t> rtcm_ids;
277277
std::vector<int64_t> rtcm_rates;
278278
this->get_parameter("rtcm.ids", rtcm_ids);
@@ -319,11 +319,11 @@ void UbloxNode::getRosParams() {
319319

320320

321321
this->declare_parameter("dat.set", false);
322-
this->declare_parameter<double>("dat.majA");
323-
this->declare_parameter<double>("dat.flat");
324-
this->declare_parameter<std::vector<double>>("dat.shift");
325-
this->declare_parameter<std::vector<double>>("dat.rot");
326-
this->declare_parameter<double>("dat.scale");
322+
this->declare_parameter("dat.majA", rclcpp::PARAMETER_DOUBLE);
323+
this->declare_parameter("dat.flat", rclcpp::PARAMETER_DOUBLE);
324+
this->declare_parameter("dat.shift", rclcpp::PARAMETER_DOUBLE_ARRAY);
325+
this->declare_parameter("dat.rot", rclcpp::PARAMETER_DOUBLE_ARRAY);
326+
this->declare_parameter("dat.scale", rclcpp::PARAMETER_DOUBLE);
327327
if (getRosBoolean(this, "dat.set")) {
328328
std::vector<double> shift, rot;
329329
if (!this->get_parameter("dat.majA", cfg_dat_.maj_a)
@@ -368,7 +368,7 @@ void UbloxNode::getRosParams() {
368368
this->declare_parameter("sv_in.min_dur", 0);
369369
this->declare_parameter("sv_in.acc_lim", 0.0);
370370

371-
this->declare_parameter<int64_t>("dgnss_mode");
371+
this->declare_parameter("dgnss_mode", rclcpp::PARAMETER_INTEGER);
372372

373373
// raw data stream logging
374374
this->declare_parameter("raw_data_stream.enable", false);
@@ -450,9 +450,9 @@ void UbloxNode::getRosParams() {
450450
// HNR parameters
451451
this->declare_parameter("publish.hnr.pvt", true);
452452

453-
this->declare_parameter<int64_t>("tmode3");
454-
this->declare_parameter<std::vector<double>>("arp.position");
455-
this->declare_parameter<std::vector<int64_t>>("arp.position_hp");
453+
this->declare_parameter("tmode3", rclcpp::PARAMETER_INTEGER);
454+
this->declare_parameter("arp.position", rclcpp::PARAMETER_DOUBLE_ARRAY);
455+
this->declare_parameter("arp.position_hp", rclcpp::PARAMETER_INTEGER_ARRAY);
456456
this->declare_parameter("arp.acc", 0.0);
457457
this->declare_parameter("arp.lla_flag", false);
458458

0 commit comments

Comments
 (0)