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
This commit is contained in:
Matthias Grob
2024-06-18 16:44:11 +02:00
parent ac13fb77a9
commit e2c80c7970
6 changed files with 7 additions and 7 deletions
+1 -1
View File
@@ -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
@@ -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;
+1 -1
View File
@@ -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;
+2 -2
View File
@@ -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;
+1 -1
View File
@@ -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);
@@ -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;
}