Skip to content

Commit 055f8bf

Browse files
Add parameter for publish nan on unmeasured bs fields
1 parent 607da9e commit 055f8bf

File tree

3 files changed

+35
-4
lines changed

3 files changed

+35
-4
lines changed

tr1200_base/include/tr1200_base/hardware.hpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -118,6 +118,9 @@ class TR1200Interface : public hardware_interface::SystemInterface
118118

119119
// Battery state publisher
120120
rclcpp::Publisher<BatteryState>::SharedPtr pub_battery_state_;
121+
122+
// True to publish unmeasured battery state values as NaNs, false to publish -1s
123+
bool publish_battery_state_nans_{false};
121124
};
122125

123126
} // namespace tr1200_base

tr1200_base/src/hardware.cpp

Lines changed: 31 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -59,6 +59,16 @@ CallbackReturn TR1200Interface::on_init(const hardware_interface::HardwareInfo &
5959
"Will connect to port '%s' on activation.",
6060
port_name_.c_str());
6161

62+
try {
63+
publish_battery_state_nans_ = info_.hardware_parameters.at("publish_battery_state_nans") == "true";
64+
} catch (const std::out_of_range & /* e */) {
65+
RCLCPP_DEBUG(
66+
node_->get_logger(),
67+
"Could not find publish_battery_state_nans in hardware parameters, setting to default of "
68+
"'false'.");
69+
publish_battery_state_nans_ = false;
70+
}
71+
6272
// get joint names from parameters
6373
try {
6474
joint_name_left_wheel_ = info_.hardware_parameters.at("joint_name_left_wheel");
@@ -256,13 +266,30 @@ return_type TR1200Interface::read(
256266
// Read and publish battery state
257267
auto battery_state = BatteryState();
258268
battery_state.header.stamp = node_->now();
269+
battery_state.power_supply_technology = BatteryState::POWER_SUPPLY_TECHNOLOGY_LIFE;
270+
battery_state.power_supply_status = BatteryState::POWER_SUPPLY_STATUS_UNKNOWN;
271+
battery_state.power_supply_health = BatteryState::POWER_SUPPLY_HEALTH_UNKNOWN;
272+
259273
battery_state.voltage = driver_->get_battery_voltage();
260-
battery_state.current = driver_->get_battery_current();
261-
battery_state.charge = std::numeric_limits<float>::quiet_NaN();
262-
battery_state.capacity = std::numeric_limits<float>::quiet_NaN();
263-
battery_state.design_capacity = std::numeric_limits<float>::quiet_NaN();
264274
battery_state.percentage = driver_->get_battery_soc();
265275
battery_state.present = true;
276+
// TODO(lukeschmitt-tr): Reenable this once current has been verified
277+
// battery_state.current = driver_->get_battery_current();
278+
279+
if (publish_battery_state_nans_) {
280+
battery_state.charge = std::numeric_limits<float>::quiet_NaN();
281+
battery_state.capacity = std::numeric_limits<float>::quiet_NaN();
282+
battery_state.design_capacity = std::numeric_limits<float>::quiet_NaN();
283+
battery_state.temperature = std::numeric_limits<float>::quiet_NaN();
284+
battery_state.current = std::numeric_limits<float>::quiet_NaN();
285+
} else {
286+
battery_state.charge = -1.0;
287+
battery_state.capacity = -1.0;
288+
battery_state.design_capacity = -1.0;
289+
battery_state.temperature = -1.0;
290+
battery_state.current = -1.0;
291+
}
292+
266293
pub_battery_state_->publish(battery_state);
267294

268295
return return_type::OK;

tr1200_description/urdf/tr1200.ros2_control.xacro

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919
<hardware>
2020
<plugin>tr1200_base/TR1200Interface</plugin>
2121
<param name="port_name">can0</param>
22+
<param name="publish_battery_state_nans">false</param>
2223
<param name="joint_name_left_wheel">${left_wheel_joint}</param>
2324
<param name="joint_name_right_wheel">${right_wheel_joint}</param>
2425
</hardware>

0 commit comments

Comments
 (0)