Skip to content

Commit

Permalink
GCS_MAVLink: accept accel cal vehicle positions as both int and long
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker committed Oct 12, 2023
1 parent 14b6776 commit 659db36
Show file tree
Hide file tree
Showing 2 changed files with 7 additions and 8 deletions.
2 changes: 1 addition & 1 deletion libraries/GCS_MAVLink/GCS.h
Original file line number Diff line number Diff line change
Expand Up @@ -638,7 +638,7 @@ class GCS_MAVLINK

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

#if HAL_MOUNT_ENABLED
virtual MAV_RESULT handle_command_mount(const mavlink_command_int_t &packet, const mavlink_message_t &msg);
Expand Down
13 changes: 6 additions & 7 deletions libraries/GCS_MAVLink/GCS_Common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4635,7 +4635,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_airframe_configuration(const mavlink_comm
#endif

#if HAL_INS_ACCELCAL_ENABLED
MAV_RESULT GCS_MAVLINK::handle_command_accelcal_vehicle_pos(const mavlink_command_long_t &packet)
MAV_RESULT GCS_MAVLINK::handle_command_accelcal_vehicle_pos(const mavlink_command_int_t &packet)
{
if (AP::ins().get_acal() == nullptr ||
!AP::ins().get_acal()->gcs_vehicle_position(packet.param1)) {
Expand Down Expand Up @@ -4727,12 +4727,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t

switch (packet.command) {

#if HAL_INS_ACCELCAL_ENABLED
case MAV_CMD_ACCELCAL_VEHICLE_POS:
result = handle_command_accelcal_vehicle_pos(packet);
break;
#endif

case MAV_CMD_DO_SET_MODE:
result = handle_command_do_set_mode(packet);
break;
Expand Down Expand Up @@ -5087,6 +5081,11 @@ MAV_RESULT GCS_MAVLINK::handle_command_storage_format(const mavlink_command_int_
MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
{
switch (packet.command) {
#if HAL_INS_ACCELCAL_ENABLED
case MAV_CMD_ACCELCAL_VEHICLE_POS:
return handle_command_accelcal_vehicle_pos(packet);
#endif

#if AP_LANDINGGEAR_ENABLED
case MAV_CMD_AIRFRAME_CONFIGURATION:
return handle_command_airframe_configuration(packet);
Expand Down

0 comments on commit 659db36

Please sign in to comment.