Browse Source

GCS_MAVLink: add common handling of mavlink command messages

master
Peter Barker 8 years ago committed by Francisco Ferreira
parent
commit
cfc8d7feba
  1. 2
      libraries/GCS_MAVLink/GCS.h
  2. 12
      libraries/GCS_MAVLink/GCS_Common.cpp

2
libraries/GCS_MAVLink/GCS.h

@ -273,6 +273,8 @@ protected: @@ -273,6 +273,8 @@ protected:
bool telemetry_delayed() const;
virtual uint32_t telem_delay() const = 0;
MAV_RESULT handle_command_long_message(mavlink_command_long_t &packet);
private:
float adjust_rate_for_stream_trigger(enum streams stream_num);

12
libraries/GCS_MAVLink/GCS_Common.cpp

@ -1835,6 +1835,18 @@ void GCS_MAVLINK::handle_common_mission_message(mavlink_message_t *msg) @@ -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()
{
return *GCS::instance();

Loading…
Cancel
Save