diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 4b8ac66105..f9eea363e8 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -620,6 +620,20 @@ MavlinkReceiver::handle_message_command_ack(mavlink_message_t *msg) MavlinkCommandSender::instance().handle_mavlink_command_ack(ack, msg->sysid, msg->compid); + vehicle_command_ack_s command_ack = {}; + command_ack.command = ack.command; + command_ack.result = ack.result; + command_ack.timestamp = hrt_absolute_time(); + + if (_command_ack_pub == nullptr) { + _command_ack_pub = orb_advertise_queue(ORB_ID(vehicle_command_ack), &command_ack, + vehicle_command_ack_s::ORB_QUEUE_LENGTH); + + } else { + orb_publish(ORB_ID(vehicle_command_ack), _command_ack_pub, &command_ack); + } + + // TODO: move it to the same place that sent the command if (ack.result != MAV_RESULT_ACCEPTED && ack.result != MAV_RESULT_IN_PROGRESS) { if (msg->compid == MAV_COMP_ID_CAMERA) { PX4_WARN("Got unsuccessful result %d from camera", ack.result);