mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: use subclasses in vehicle directories
Instead of the vehicles defining functions that are declared in the libraries directory, they will now create subclasses of GCS_MAVLINK
This commit is contained in:
parent
d67f83559c
commit
56114dd37a
|
@ -93,7 +93,7 @@ public:
|
|||
void setup_uart(const AP_SerialManager& serial_manager, AP_SerialManager::SerialProtocol protocol, uint8_t instance);
|
||||
void send_message(enum ap_message id);
|
||||
void send_text(MAV_SEVERITY severity, const char *str);
|
||||
void data_stream_send(void);
|
||||
virtual void data_stream_send(void) = 0;
|
||||
void queued_param_send();
|
||||
void queued_waypoint_send();
|
||||
void set_snoop(void (*_msg_snoop)(const mavlink_message_t* msg)) {
|
||||
|
@ -211,18 +211,58 @@ public:
|
|||
// return current packet overhead for a channel
|
||||
static uint8_t packet_overhead_chan(mavlink_channel_t chan);
|
||||
|
||||
private:
|
||||
float adjust_rate_for_stream_trigger(enum streams stream_num);
|
||||
protected:
|
||||
|
||||
void handleMessage(mavlink_message_t * msg);
|
||||
bool waypoint_receiving; // currently receiving
|
||||
// the following two variables are only here because of Tracker
|
||||
uint16_t waypoint_request_i; // request index
|
||||
uint16_t waypoint_request_last; // last request index
|
||||
|
||||
AP_Param * _queued_parameter; ///< next parameter to
|
||||
// be sent in queue
|
||||
mavlink_channel_t chan;
|
||||
uint8_t packet_overhead(void) const { return packet_overhead_chan(chan); }
|
||||
|
||||
void handle_log_send(DataFlash_Class &dataflash);
|
||||
|
||||
// saveable rate of each stream
|
||||
AP_Int16 streamRates[NUM_STREAMS];
|
||||
|
||||
void handle_request_data_stream(mavlink_message_t *msg, bool save);
|
||||
FUNCTOR_TYPEDEF(set_mode_fn, bool, uint8_t);
|
||||
void handle_set_mode(mavlink_message_t* msg, set_mode_fn set_mode);
|
||||
|
||||
void handle_mission_request_list(AP_Mission &mission, mavlink_message_t *msg);
|
||||
void handle_mission_request(AP_Mission &mission, mavlink_message_t *msg);
|
||||
void handle_mission_clear_all(AP_Mission &mission, mavlink_message_t *msg);
|
||||
void handle_mission_set_current(AP_Mission &mission, mavlink_message_t *msg);
|
||||
void handle_mission_count(AP_Mission &mission, mavlink_message_t *msg);
|
||||
void handle_mission_write_partial_list(AP_Mission &mission, mavlink_message_t *msg);
|
||||
bool handle_mission_item(mavlink_message_t *msg, AP_Mission &mission);
|
||||
|
||||
void handle_param_set(mavlink_message_t *msg, DataFlash_Class *DataFlash);
|
||||
void handle_param_request_list(mavlink_message_t *msg);
|
||||
void handle_param_request_read(mavlink_message_t *msg);
|
||||
|
||||
void handle_gimbal_report(AP_Mount &mount, mavlink_message_t *msg) const;
|
||||
void handle_radio_status(mavlink_message_t *msg, DataFlash_Class &dataflash, bool log_radio);
|
||||
void handle_serial_control(mavlink_message_t *msg, AP_GPS &gps);
|
||||
|
||||
void handle_gps_inject(const mavlink_message_t *msg, AP_GPS &gps);
|
||||
|
||||
void handle_log_message(mavlink_message_t *msg, DataFlash_Class &dataflash);
|
||||
void handle_setup_signing(const mavlink_message_t *msg);
|
||||
|
||||
private:
|
||||
virtual float adjust_rate_for_stream_trigger(enum streams stream_num) = 0;
|
||||
|
||||
virtual void handleMessage(mavlink_message_t * msg) = 0;
|
||||
|
||||
/// The stream we are communicating over
|
||||
AP_HAL::UARTDriver *_port;
|
||||
|
||||
/// Perform queued sending operations
|
||||
///
|
||||
AP_Param * _queued_parameter; ///< next parameter to
|
||||
// be sent in queue
|
||||
enum ap_var_type _queued_parameter_type; ///< type of the next
|
||||
// parameter
|
||||
AP_Param::ParamToken _queued_parameter_token; ///AP_Param token for
|
||||
|
@ -244,26 +284,19 @@ private:
|
|||
///
|
||||
/// @return The number of reportable parameters.
|
||||
///
|
||||
mavlink_channel_t chan;
|
||||
uint16_t packet_drops;
|
||||
|
||||
// this allows us to detect the user wanting the CLI to start
|
||||
uint8_t crlf_count;
|
||||
|
||||
// waypoints
|
||||
uint16_t waypoint_request_i; // request index
|
||||
uint16_t waypoint_request_last; // last request index
|
||||
uint16_t waypoint_dest_sysid; // where to send requests
|
||||
uint16_t waypoint_dest_compid; // "
|
||||
bool waypoint_receiving; // currently receiving
|
||||
uint16_t waypoint_count;
|
||||
uint32_t waypoint_timelast_receive; // milliseconds
|
||||
uint32_t waypoint_timelast_request; // milliseconds
|
||||
const uint16_t waypoint_receive_timeout = 8000; // milliseconds
|
||||
|
||||
// saveable rate of each stream
|
||||
AP_Int16 streamRates[NUM_STREAMS];
|
||||
|
||||
// number of 50Hz ticks until we next send this stream
|
||||
uint8_t stream_ticks[NUM_STREAMS];
|
||||
|
||||
|
@ -324,41 +357,20 @@ private:
|
|||
static void (*msg_snoop)(const mavlink_message_t* msg);
|
||||
|
||||
// vehicle specific message send function
|
||||
bool try_send_message(enum ap_message id);
|
||||
virtual bool try_send_message(enum ap_message id) = 0;
|
||||
|
||||
bool handle_guided_request(AP_Mission::Mission_Command &cmd);
|
||||
void handle_change_alt_request(AP_Mission::Mission_Command &cmd);
|
||||
virtual bool handle_guided_request(AP_Mission::Mission_Command &cmd) = 0;
|
||||
virtual void handle_change_alt_request(AP_Mission::Mission_Command &cmd) = 0;
|
||||
|
||||
void handle_log_request_list(mavlink_message_t *msg, DataFlash_Class &dataflash);
|
||||
void handle_log_request_data(mavlink_message_t *msg, DataFlash_Class &dataflash);
|
||||
void handle_log_request_erase(mavlink_message_t *msg, DataFlash_Class &dataflash);
|
||||
void handle_log_request_end(mavlink_message_t *msg, DataFlash_Class &dataflash);
|
||||
void handle_log_message(mavlink_message_t *msg, DataFlash_Class &dataflash);
|
||||
void handle_log_send(DataFlash_Class &dataflash);
|
||||
void handle_log_send_listing(DataFlash_Class &dataflash);
|
||||
bool handle_log_send_data(DataFlash_Class &dataflash);
|
||||
|
||||
void handle_mission_request_list(AP_Mission &mission, mavlink_message_t *msg);
|
||||
void handle_mission_request(AP_Mission &mission, mavlink_message_t *msg);
|
||||
|
||||
void handle_mission_set_current(AP_Mission &mission, mavlink_message_t *msg);
|
||||
void handle_mission_count(AP_Mission &mission, mavlink_message_t *msg);
|
||||
void handle_mission_clear_all(AP_Mission &mission, mavlink_message_t *msg);
|
||||
void handle_mission_write_partial_list(AP_Mission &mission, mavlink_message_t *msg);
|
||||
bool handle_mission_item(mavlink_message_t *msg, AP_Mission &mission);
|
||||
|
||||
void handle_request_data_stream(mavlink_message_t *msg, bool save);
|
||||
void handle_param_request_list(mavlink_message_t *msg);
|
||||
void handle_param_request_read(mavlink_message_t *msg);
|
||||
void handle_param_set(mavlink_message_t *msg, DataFlash_Class *DataFlash);
|
||||
void handle_radio_status(mavlink_message_t *msg, DataFlash_Class &dataflash, bool log_radio);
|
||||
void handle_serial_control(mavlink_message_t *msg, AP_GPS &gps);
|
||||
void lock_channel(mavlink_channel_t chan, bool lock);
|
||||
FUNCTOR_TYPEDEF(set_mode_fn, bool, uint8_t);
|
||||
void handle_set_mode(mavlink_message_t* msg, set_mode_fn set_mode);
|
||||
void handle_gimbal_report(AP_Mount &mount, mavlink_message_t *msg) const;
|
||||
|
||||
void handle_gps_inject(const mavlink_message_t *msg, AP_GPS &gps);
|
||||
|
||||
// return true if this channel has hardware flow control
|
||||
bool have_flow_control(void);
|
||||
|
@ -368,11 +380,9 @@ private:
|
|||
static uint32_t last_signing_save_ms;
|
||||
|
||||
static StorageAccess _signing_storage;
|
||||
void handle_setup_signing(const mavlink_message_t *msg);
|
||||
static bool signing_key_save(const struct SigningKey &key);
|
||||
static bool signing_key_load(struct SigningKey &key);
|
||||
void load_signing_key(void);
|
||||
bool signing_enabled(void) const;
|
||||
uint8_t packet_overhead(void) const { return packet_overhead_chan(chan); }
|
||||
static void save_signing_timestamp(bool force_save_now);
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue