From e2c80c7970fcc0a3040c5c6bf2079699622ac659 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Tue, 18 Jun 2024 16:44:11 +0200 Subject: [PATCH] vehicle_command_ack: rename `result_param1` to `progress` and comment usage To avoid confusion: - naming consistent with MAVLink definition - comments about the few different ways the field is used --- msg/VehicleCommandAck.msg | 2 +- .../commander/Arming/ArmAuthorization/ArmAuthorization.cpp | 2 +- src/modules/mavlink/mavlink_main.cpp | 2 +- src/modules/mavlink/mavlink_receiver.cpp | 4 ++-- src/modules/navigator/navigator_main.cpp | 2 +- src/modules/payload_deliverer/payload_deliverer.cpp | 2 +- 6 files changed, 7 insertions(+), 7 deletions(-) diff --git a/msg/VehicleCommandAck.msg b/msg/VehicleCommandAck.msg index 6f54fa4631..e7d4a8f5ea 100644 --- a/msg/VehicleCommandAck.msg +++ b/msg/VehicleCommandAck.msg @@ -25,7 +25,7 @@ uint8 ORB_QUEUE_LENGTH = 4 uint32 command # Command that is being acknowledged uint8 result # Command result -uint8 result_param1 # Also used as progress[%], it can be set with the reason why the command was denied, or the progress percentage when result is MAV_RESULT_IN_PROGRESS +uint8 progress # Also used as progress[%], it can be set with the reason why the command was denied, or the progress percentage when result is MAV_RESULT_IN_PROGRESS int32 result_param2 # Additional parameter of the result, example: which parameter of MAV_CMD_NAV_WAYPOINT caused it to be denied. uint8 target_system uint16 target_component # Target component / mode executor diff --git a/src/modules/commander/Arming/ArmAuthorization/ArmAuthorization.cpp b/src/modules/commander/Arming/ArmAuthorization/ArmAuthorization.cpp index bfcff4a3ae..9a811c727e 100644 --- a/src/modules/commander/Arming/ArmAuthorization/ArmAuthorization.cpp +++ b/src/modules/commander/Arming/ArmAuthorization/ArmAuthorization.cpp @@ -251,7 +251,7 @@ void arm_auth_update(hrt_abstime now, bool param_update) case vehicle_command_ack_s::VEHICLE_CMD_RESULT_DENIED: default: - switch (command_ack.result_param1) { + switch (command_ack.progress) { // It's not used as progress but as protocol parameter for arm authorization case vehicle_command_ack_s::ARM_AUTH_DENIED_REASON_NONE: /* Authorizer will send reason to ground station */ break; diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 54e1a8549e..2955ddd520 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -2604,7 +2604,7 @@ void Mavlink::handleAndGetCurrentCommandAck() mavlink_command_ack_t msg{}; msg.result = command_ack.result; msg.command = command_ack.command; - msg.progress = command_ack.result_param1; + msg.progress = command_ack.progress; msg.result_param2 = command_ack.result_param2; msg.target_system = command_ack.target_system; msg.target_component = command_ack.target_component; diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 35e2879c6d..afcca3c4e0 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -127,7 +127,7 @@ MavlinkReceiver::acknowledge(uint8_t sysid, uint8_t compid, uint16_t command, ui command_ack.result = result; command_ack.target_system = sysid; command_ack.target_component = compid; - command_ack.result_param1 = progress; + command_ack.progress = progress; _cmd_ack_pub.publish(command_ack); } @@ -771,7 +771,7 @@ MavlinkReceiver::handle_message_command_ack(mavlink_message_t *msg) command_ack.command = ack.command; command_ack.result = ack.result; command_ack.from_external = true; - command_ack.result_param1 = ack.progress; + command_ack.progress = ack.progress; command_ack.target_system = ack.target_system; command_ack.target_component = ack.target_component; diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index d5ea7ac22d..a9eb62e8f8 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -1418,7 +1418,7 @@ void Navigator::publish_vehicle_command_ack(const vehicle_command_s &cmd, uint8_ command_ack.from_external = false; command_ack.result = result; - command_ack.result_param1 = 0; + command_ack.progress = 0; command_ack.result_param2 = 0; _vehicle_cmd_ack_pub.publish(command_ack); diff --git a/src/modules/payload_deliverer/payload_deliverer.cpp b/src/modules/payload_deliverer/payload_deliverer.cpp index 0edb3a5270..3c12f7641a 100644 --- a/src/modules/payload_deliverer/payload_deliverer.cpp +++ b/src/modules/payload_deliverer/payload_deliverer.cpp @@ -255,7 +255,7 @@ bool PayloadDeliverer::send_gripper_vehicle_command_ack(const hrt_abstime now, c switch (command_result) { case vehicle_command_ack_s::VEHICLE_CMD_RESULT_IN_PROGRESS: // Fill in the progress percentage field for IN_PROGRESS ack message - vcmd_ack.result_param1 = UINT8_MAX; + vcmd_ack.progress = UINT8_MAX; // unkown progress according to MAVLink definition break; }