@@ -59,6 +59,16 @@ CallbackReturn TR1200Interface::on_init(const hardware_interface::HardwareInfo &
59
59
" Will connect to port '%s' on activation." ,
60
60
port_name_.c_str ());
61
61
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
+
62
72
// get joint names from parameters
63
73
try {
64
74
joint_name_left_wheel_ = info_.hardware_parameters .at (" joint_name_left_wheel" );
@@ -256,13 +266,30 @@ return_type TR1200Interface::read(
256
266
// Read and publish battery state
257
267
auto battery_state = BatteryState ();
258
268
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
+
259
273
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 ();
264
274
battery_state.percentage = driver_->get_battery_soc ();
265
275
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
+
266
293
pub_battery_state_->publish (battery_state);
267
294
268
295
return return_type::OK;
0 commit comments