mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
GCS_MAVLink: add common handling of mavlink command messages
This commit is contained in:
parent
6b60c110a5
commit
cfc8d7feba
@ -273,6 +273,8 @@ protected:
|
|||||||
bool telemetry_delayed() const;
|
bool telemetry_delayed() const;
|
||||||
virtual uint32_t telem_delay() const = 0;
|
virtual uint32_t telem_delay() const = 0;
|
||||||
|
|
||||||
|
MAV_RESULT handle_command_long_message(mavlink_command_long_t &packet);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
float adjust_rate_for_stream_trigger(enum streams stream_num);
|
float adjust_rate_for_stream_trigger(enum streams stream_num);
|
||||||
|
@ -1835,6 +1835,18 @@ void GCS_MAVLINK::handle_common_mission_message(mavlink_message_t *msg)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
MAV_RESULT GCS_MAVLINK::handle_command_long_message(mavlink_command_long_t &packet)
|
||||||
|
{
|
||||||
|
MAV_RESULT result = MAV_RESULT_FAILED;
|
||||||
|
|
||||||
|
switch (packet.command) {
|
||||||
|
default:
|
||||||
|
result = MAV_RESULT_UNSUPPORTED;
|
||||||
|
}
|
||||||
|
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
|
||||||
GCS &gcs()
|
GCS &gcs()
|
||||||
{
|
{
|
||||||
return *GCS::instance();
|
return *GCS::instance();
|
||||||
|
Loading…
Reference in New Issue
Block a user