Skip to content

Commit 0deb39c

Browse files
authored
Merge pull request #258 from chen-gr/master
Rename cap message variables
2 parents 4aa44e7 + 7c78418 commit 0deb39c

File tree

2 files changed

+4
-5
lines changed

2 files changed

+4
-5
lines changed

rm_msgs/msg/referee/PowerManagementSampleAndStatusData.msg

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
float32 chassis_power
2-
float32 chassis_expect_power
3-
float32 capacity_recent_charge_power
2+
float32 cap_error_flag
3+
float32 cap_received_msg
44
float32 capacity_remain_charge
55
uint8 capacity_discharge_power
66
uint8 state_machine_running_state

rm_referee/src/referee.cpp

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -555,9 +555,8 @@ int Referee::unpack(uint8_t* rx_data)
555555
uint8_t data[sizeof(rm_referee::PowerManagementSampleAndStatusData)];
556556
memcpy(&data, rx_data + 7, sizeof(rm_referee::PowerManagementSampleAndStatusData));
557557
sample_and_status_pub_data.chassis_power = (static_cast<uint16_t>((data[0] << 8) | data[1]) / 100.);
558-
sample_and_status_pub_data.chassis_expect_power = (static_cast<uint16_t>((data[2] << 8) | data[3]) / 100.);
559-
sample_and_status_pub_data.capacity_recent_charge_power =
560-
(static_cast<uint16_t>((data[4] << 8) | data[5]) / 100.);
558+
sample_and_status_pub_data.cap_error_flag = (static_cast<uint16_t>((data[2] << 8) | data[3]) / 100.);
559+
sample_and_status_pub_data.cap_received_msg = (static_cast<uint16_t>((data[4] << 8) | data[5]) / 100.);
561560
sample_and_status_pub_data.capacity_remain_charge =
562561
(static_cast<uint16_t>((data[6] << 8) | data[7]) / 10000.);
563562
sample_and_status_pub_data.capacity_discharge_power = static_cast<uint8_t>(data[8]);

0 commit comments

Comments
 (0)