From 57f9b7236acc571e32a435f04d9958c30c154834 Mon Sep 17 00:00:00 2001 From: hanskw4267 Date: Mon, 15 Jan 2024 10:00:18 +0800 Subject: [PATCH] src: sample: fix ranger demo --- sample/ranger_demo/ranger_robot_demo.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/sample/ranger_demo/ranger_robot_demo.cpp b/sample/ranger_demo/ranger_robot_demo.cpp index 3f9d79b8..55facea6 100644 --- a/sample/ranger_demo/ranger_robot_demo.cpp +++ b/sample/ranger_demo/ranger_robot_demo.cpp @@ -49,6 +49,7 @@ int main(int argc, char *argv[]) { auto state = ranger->GetRobotState(); auto motion = ranger->GetActuatorState(); + auto sensor = ranger->GetCommonSensorState(); std::cout << "-------------------------------" << std::endl; std::cout << "count: " << count << std::endl; @@ -58,9 +59,10 @@ int main(int argc, char *argv[]) { << static_cast(state.system_state.vehicle_state) << std::endl; std::cout << "battery voltage: " << state.system_state.battery_voltage - << ", battery current: " << state.bms_basic_state.current + << "battery voltage (BMS): " << sensor.bms_basic_state.voltage + << ", battery current: " << sensor.bms_basic_state.current << ", SOC: " - << static_cast(state.bms_basic_state.battery_soc) + << static_cast(sensor.bms_basic_state.battery_soc) << std::endl; std::cout << "velocity (linear, angular, lateral, steering): " << std::setw(6) << state.motion_state.linear_velocity << ", "