mavlink: send ACK for CMD_SET_MESSAGE_INTERVAL

There was no feedback if a CMD_SET_MESSAGE_INTERVAL went through or not.
This commit is contained in:
Julian Oes 2016-11-08 16:09:33 +01:00 committed by Beat Küng
parent 643ccd66b6
commit 1e617f362d
2 changed files with 16 additions and 5 deletions

View File

@ -82,6 +82,8 @@
#include <commander/px4_custom_mode.h>
#include <geo/geo.h>
#include <uORB/topics/vehicle_command_ack.h>
#include "mavlink_bridge_header.h"
#include "mavlink_receiver.h"
#include "mavlink_main.h"
@ -128,6 +130,7 @@ MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
_transponder_report_pub(nullptr),
_control_state_pub(nullptr),
_gps_inject_data_pub(nullptr),
_command_ack_pub(nullptr),
_control_mode_sub(orb_subscribe(ORB_ID(vehicle_control_mode))),
_hil_frames(0),
_old_timestamp(0),
@ -374,6 +377,13 @@ MavlinkReceiver::handle_message_command_long(mavlink_message_t *msg)
} else if (cmd_mavlink.command == MAV_CMD_SET_MESSAGE_INTERVAL) {
set_message_interval((int)(cmd_mavlink.param1 + 0.5f), cmd_mavlink.param2, cmd_mavlink.param3);
vehicle_command_ack_s command_ack;
command_ack.command = cmd_mavlink.command;
command_ack.result = vehicle_command_ack_s::VEHICLE_RESULT_ACCEPTED;
int instance;
orb_publish_auto(ORB_ID(vehicle_command_ack), &_command_ack_pub, &command_ack, &instance, ORB_PRIO_DEFAULT);
} else if (cmd_mavlink.command == MAV_CMD_GET_MESSAGE_INTERVAL) {
get_message_interval((int)cmd_mavlink.param1);

View File

@ -224,6 +224,7 @@ private:
orb_advert_t _control_state_pub;
static const int _gps_inject_data_queue_size = 6;
orb_advert_t _gps_inject_data_pub;
orb_advert_t _command_ack_pub;
int _control_mode_sub;
int _hil_frames;
uint64_t _old_timestamp;