Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Handle MAV_CMD_BATTERY_RESET as both long and int #25471

Merged
merged 2 commits into from
Nov 8, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
15 changes: 15 additions & 0 deletions Tools/autotest/rover.py
Original file line number Diff line number Diff line change
Expand Up @@ -6614,6 +6614,20 @@ def MAV_CMD_DO_FENCE_ENABLE(self):
self.run_cmd_int(mavutil.mavlink.MAV_CMD_DO_FENCE_ENABLE, p1=0)
self.assert_fence_disabled()

def MAV_CMD_BATTERY_RESET(self):
'''manipulate battery levels with MAV_CMD_BATTERY_RESET'''
for (run_cmd, value) in (self.run_cmd, 56), (self.run_cmd_int, 97):
run_cmd(
mavutil.mavlink.MAV_CMD_BATTERY_RESET,
p1=65535, # battery mask
p2=value,
)
self.assert_received_message_field_values('BATTERY_STATUS', {
"battery_remaining": value,
}, {
"poll": True,
})

def tests(self):
'''return list of all tests'''
ret = super(AutoTestRover, self).tests()
Expand Down Expand Up @@ -6697,6 +6711,7 @@ def tests(self):
self.MAV_CMD_DO_SET_REVERSE,
self.MAV_CMD_GET_HOME_POSITION,
self.MAV_CMD_DO_FENCE_ENABLE,
self.MAV_CMD_BATTERY_RESET,
])
return ret

Expand Down
2 changes: 1 addition & 1 deletion libraries/GCS_MAVLink/GCS.h
Original file line number Diff line number Diff line change
Expand Up @@ -640,7 +640,7 @@ class GCS_MAVLINK

virtual MAV_RESULT handle_command_do_set_mission_current(const mavlink_command_long_t &packet);

MAV_RESULT handle_command_battery_reset(const mavlink_command_long_t &packet);
MAV_RESULT handle_command_battery_reset(const mavlink_command_int_t &packet);
void handle_command_long(const mavlink_message_t &msg);
MAV_RESULT handle_command_accelcal_vehicle_pos(const mavlink_command_int_t &packet);

Expand Down
14 changes: 7 additions & 7 deletions libraries/GCS_MAVLink/GCS_Common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4476,7 +4476,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_set_mission_current(const mavlink_comm
}

#if AP_BATTERY_ENABLED
MAV_RESULT GCS_MAVLINK::handle_command_battery_reset(const mavlink_command_long_t &packet)
MAV_RESULT GCS_MAVLINK::handle_command_battery_reset(const mavlink_command_int_t &packet)
{
const uint16_t battery_mask = packet.param1;
const float percentage = packet.param2;
Expand Down Expand Up @@ -4744,12 +4744,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t
result = handle_command_do_set_mission_current(packet);
break;

#if AP_BATTERY_ENABLED
case MAV_CMD_BATTERY_RESET:
result = handle_command_battery_reset(packet);
break;
#endif

default:
result = try_command_long_as_command_int(packet, msg);
break;
Expand Down Expand Up @@ -5016,6 +5010,12 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p
case MAV_CMD_AIRFRAME_CONFIGURATION:
return handle_command_airframe_configuration(packet);
#endif

#if AP_BATTERY_ENABLED
case MAV_CMD_BATTERY_RESET:
return handle_command_battery_reset(packet);
#endif

#if HAL_CANMANAGER_ENABLED
case MAV_CMD_CAN_FORWARD:
return handle_can_forward(packet, msg);
Expand Down