Skip to content

Commit 60554fd

Browse files
Change parameter default to true, lint
1 parent 055f8bf commit 60554fd

File tree

2 files changed

+5
-4
lines changed

2 files changed

+5
-4
lines changed

tr1200_base/include/tr1200_base/hardware.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -120,7 +120,7 @@ class TR1200Interface : public hardware_interface::SystemInterface
120120
rclcpp::Publisher<BatteryState>::SharedPtr pub_battery_state_;
121121

122122
// True to publish unmeasured battery state values as NaNs, false to publish -1s
123-
bool publish_battery_state_nans_{false};
123+
bool publish_battery_state_nans_{true};
124124
};
125125

126126
} // namespace tr1200_base

tr1200_base/src/hardware.cpp

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -60,13 +60,14 @@ CallbackReturn TR1200Interface::on_init(const hardware_interface::HardwareInfo &
6060
port_name_.c_str());
6161

6262
try {
63-
publish_battery_state_nans_ = info_.hardware_parameters.at("publish_battery_state_nans") == "true";
63+
publish_battery_state_nans_ =
64+
info_.hardware_parameters.at("publish_battery_state_nans") == "true";
6465
} catch (const std::out_of_range & /* e */) {
6566
RCLCPP_DEBUG(
6667
node_->get_logger(),
6768
"Could not find publish_battery_state_nans in hardware parameters, setting to default of "
68-
"'false'.");
69-
publish_battery_state_nans_ = false;
69+
"'true'.");
70+
publish_battery_state_nans_ = true;
7071
}
7172

7273
// get joint names from parameters

0 commit comments

Comments
 (0)