2011-02-17 05:36:33 -04:00
|
|
|
/// @file GCS.h
|
2012-08-16 21:50:03 -03:00
|
|
|
/// @brief Interface definition for the various Ground Control System
|
|
|
|
// protocols.
|
2016-02-17 21:25:55 -04:00
|
|
|
#pragma once
|
2011-02-17 05:36:33 -04:00
|
|
|
|
2015-08-11 03:28:46 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include <AP_Common/AP_Common.h>
|
|
|
|
#include "GCS_MAVLink.h"
|
|
|
|
#include <DataFlash/DataFlash.h>
|
|
|
|
#include <AP_Mission/AP_Mission.h>
|
2015-08-15 19:54:42 -03:00
|
|
|
#include <AP_BattMonitor/AP_BattMonitor.h>
|
2013-11-23 06:45:42 -04:00
|
|
|
#include <stdint.h>
|
2015-08-11 03:28:46 -03:00
|
|
|
#include "MAVLink_routing.h"
|
2015-08-15 19:54:42 -03:00
|
|
|
#include <AP_SerialManager/AP_SerialManager.h>
|
|
|
|
#include <AP_Mount/AP_Mount.h>
|
2016-05-11 03:19:15 -03:00
|
|
|
#include <AP_Avoidance/AP_Avoidance.h>
|
2016-02-23 16:50:57 -04:00
|
|
|
#include <AP_HAL/utility/RingBuffer.h>
|
2016-10-26 19:06:54 -03:00
|
|
|
#include <AP_Frsky_Telem/AP_Frsky_Telem.h>
|
2011-02-17 05:36:33 -04:00
|
|
|
|
2015-07-24 04:18:14 -03:00
|
|
|
// check if a message will fit in the payload space available
|
2016-04-05 01:09:47 -03:00
|
|
|
#define HAVE_PAYLOAD_SPACE(chan, id) (comm_get_txspace(chan) >= GCS_MAVLINK::packet_overhead_chan(chan)+MAVLINK_MSG_ID_ ## id ## _LEN)
|
|
|
|
#define CHECK_PAYLOAD_SIZE(id) if (comm_get_txspace(chan) < packet_overhead()+MAVLINK_MSG_ID_ ## id ## _LEN) return false
|
2015-07-24 04:18:14 -03:00
|
|
|
#define CHECK_PAYLOAD_SIZE2(id) if (!HAVE_PAYLOAD_SPACE(chan, id)) return false
|
|
|
|
|
2013-12-15 03:57:15 -04:00
|
|
|
// GCS Message ID's
|
|
|
|
/// NOTE: to ensure we never block on sending MAVLink messages
|
|
|
|
/// please keep each MSG_ to a single MAVLink message. If need be
|
|
|
|
/// create new MSG_ IDs for additional messages on the same
|
|
|
|
/// stream
|
|
|
|
enum ap_message {
|
|
|
|
MSG_HEARTBEAT,
|
|
|
|
MSG_ATTITUDE,
|
|
|
|
MSG_LOCATION,
|
|
|
|
MSG_EXTENDED_STATUS1,
|
|
|
|
MSG_EXTENDED_STATUS2,
|
|
|
|
MSG_NAV_CONTROLLER_OUTPUT,
|
|
|
|
MSG_CURRENT_WAYPOINT,
|
|
|
|
MSG_VFR_HUD,
|
2017-01-10 11:17:41 -04:00
|
|
|
MSG_SERVO_OUTPUT_RAW,
|
2013-12-15 03:57:15 -04:00
|
|
|
MSG_RADIO_IN,
|
|
|
|
MSG_RAW_IMU1,
|
|
|
|
MSG_RAW_IMU2,
|
|
|
|
MSG_RAW_IMU3,
|
|
|
|
MSG_GPS_RAW,
|
|
|
|
MSG_SYSTEM_TIME,
|
|
|
|
MSG_SERVO_OUT,
|
|
|
|
MSG_NEXT_WAYPOINT,
|
|
|
|
MSG_NEXT_PARAM,
|
|
|
|
MSG_STATUSTEXT,
|
|
|
|
MSG_LIMITS_STATUS,
|
|
|
|
MSG_FENCE_STATUS,
|
|
|
|
MSG_AHRS,
|
|
|
|
MSG_SIMSTATE,
|
|
|
|
MSG_HWSTATUS,
|
|
|
|
MSG_WIND,
|
|
|
|
MSG_RANGEFINDER,
|
2014-07-21 19:23:15 -03:00
|
|
|
MSG_TERRAIN,
|
2014-08-08 23:14:06 -03:00
|
|
|
MSG_BATTERY2,
|
2014-10-31 02:40:59 -03:00
|
|
|
MSG_CAMERA_FEEDBACK,
|
2014-11-17 19:00:40 -04:00
|
|
|
MSG_MOUNT_STATUS,
|
2014-12-08 00:42:05 -04:00
|
|
|
MSG_OPTICAL_FLOW,
|
2015-01-29 05:01:29 -04:00
|
|
|
MSG_GIMBAL_REPORT,
|
2015-03-07 11:50:50 -04:00
|
|
|
MSG_MAG_CAL_PROGRESS,
|
|
|
|
MSG_MAG_CAL_REPORT,
|
2015-03-10 04:00:16 -03:00
|
|
|
MSG_EKF_STATUS_REPORT,
|
2015-04-05 12:24:05 -03:00
|
|
|
MSG_LOCAL_POSITION,
|
2015-05-22 19:14:52 -03:00
|
|
|
MSG_PID_TUNING,
|
2015-06-12 03:35:31 -03:00
|
|
|
MSG_VIBRATION,
|
2015-08-07 02:33:47 -03:00
|
|
|
MSG_RPM,
|
2015-07-24 04:18:14 -03:00
|
|
|
MSG_MISSION_ITEM_REACHED,
|
2016-04-14 02:21:41 -03:00
|
|
|
MSG_POSITION_TARGET_GLOBAL_INT,
|
2016-06-15 17:57:04 -03:00
|
|
|
MSG_ADSB_VEHICLE,
|
2017-04-07 17:13:35 -03:00
|
|
|
MSG_BATTERY_STATUS,
|
2017-04-09 08:17:36 -03:00
|
|
|
MSG_AOA_SSA,
|
2017-04-13 03:57:41 -03:00
|
|
|
MSG_LANDING,
|
2013-12-15 03:57:15 -04:00
|
|
|
MSG_RETRY_DEFERRED // this must be last
|
|
|
|
};
|
|
|
|
|
2011-02-17 05:36:33 -04:00
|
|
|
///
|
|
|
|
/// @class GCS_MAVLINK
|
2014-12-09 23:39:32 -04:00
|
|
|
/// @brief MAVLink transport control class
|
2011-02-17 05:36:33 -04:00
|
|
|
///
|
2014-12-09 23:39:32 -04:00
|
|
|
class GCS_MAVLINK
|
2011-02-17 05:36:33 -04:00
|
|
|
{
|
|
|
|
public:
|
2012-08-16 21:50:03 -03:00
|
|
|
GCS_MAVLINK();
|
2015-05-24 18:55:06 -03:00
|
|
|
FUNCTOR_TYPEDEF(run_cli_fn, void, AP_HAL::UARTDriver*);
|
2017-04-28 01:35:53 -03:00
|
|
|
void update(run_cli_fn run_cli, uint32_t max_time_us=1000);
|
2015-01-23 09:45:14 -04:00
|
|
|
void init(AP_HAL::UARTDriver *port, mavlink_channel_t mav_chan);
|
2015-03-27 22:47:29 -03:00
|
|
|
void setup_uart(const AP_SerialManager& serial_manager, AP_SerialManager::SerialProtocol protocol, uint8_t instance);
|
2012-08-16 21:50:03 -03:00
|
|
|
void send_message(enum ap_message id);
|
2015-08-25 19:08:17 -03:00
|
|
|
void send_text(MAV_SEVERITY severity, const char *str);
|
2016-05-27 09:52:24 -03:00
|
|
|
virtual void data_stream_send(void) = 0;
|
2012-08-16 21:50:03 -03:00
|
|
|
void queued_param_send();
|
|
|
|
void queued_waypoint_send();
|
2014-12-09 23:31:31 -04:00
|
|
|
void set_snoop(void (*_msg_snoop)(const mavlink_message_t* msg)) {
|
|
|
|
msg_snoop = _msg_snoop;
|
|
|
|
}
|
2016-06-14 22:04:40 -03:00
|
|
|
// packetReceived is called on any successful decode of a mavlink message
|
|
|
|
virtual void packetReceived(const mavlink_status_t &status,
|
|
|
|
mavlink_message_t &msg);
|
2012-08-16 21:50:03 -03:00
|
|
|
|
2015-01-27 09:31:51 -04:00
|
|
|
// accessor for uart
|
|
|
|
AP_HAL::UARTDriver *get_uart() { return _port; }
|
|
|
|
|
2012-08-16 21:50:03 -03:00
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
2012-02-12 07:27:03 -04:00
|
|
|
|
2014-12-09 23:39:32 -04:00
|
|
|
// set to true if this GCS link is active
|
|
|
|
bool initialised;
|
|
|
|
|
2012-04-01 22:18:42 -03:00
|
|
|
// NOTE! The streams enum below and the
|
|
|
|
// set of AP_Int16 stream rates _must_ be
|
|
|
|
// kept in the same order
|
|
|
|
enum streams {STREAM_RAW_SENSORS,
|
|
|
|
STREAM_EXTENDED_STATUS,
|
|
|
|
STREAM_RC_CHANNELS,
|
|
|
|
STREAM_RAW_CONTROLLER,
|
|
|
|
STREAM_POSITION,
|
|
|
|
STREAM_EXTRA1,
|
|
|
|
STREAM_EXTRA2,
|
|
|
|
STREAM_EXTRA3,
|
|
|
|
STREAM_PARAMS,
|
2016-06-15 17:57:04 -03:00
|
|
|
STREAM_ADSB,
|
2012-04-01 22:18:42 -03:00
|
|
|
NUM_STREAMS};
|
|
|
|
|
|
|
|
// see if we should send a stream now. Called at 50Hz
|
2012-08-16 21:50:03 -03:00
|
|
|
bool stream_trigger(enum streams stream_num);
|
2012-04-01 22:18:42 -03:00
|
|
|
|
2013-03-20 23:54:04 -03:00
|
|
|
// call to reset the timeout window for entering the cli
|
|
|
|
void reset_cli_timeout();
|
2013-12-15 18:57:28 -04:00
|
|
|
|
|
|
|
uint32_t last_heartbeat_time; // milliseconds
|
|
|
|
|
2014-03-18 18:44:58 -03:00
|
|
|
// last time we got a non-zero RSSI from RADIO_STATUS
|
|
|
|
static uint32_t last_radio_status_remrssi_ms;
|
|
|
|
|
2015-07-24 04:18:14 -03:00
|
|
|
// mission item index to be sent on queued msg, delayed or not
|
|
|
|
uint16_t mission_item_reached_index = AP_MISSION_CMD_INDEX_NONE;
|
|
|
|
|
2013-12-28 01:00:19 -04:00
|
|
|
// common send functions
|
|
|
|
void send_meminfo(void);
|
2014-02-13 07:07:13 -04:00
|
|
|
void send_power_status(void);
|
2017-04-07 17:13:35 -03:00
|
|
|
void send_battery_status(const AP_BattMonitor &battery, const uint8_t instance) const;
|
|
|
|
bool send_battery_status(const AP_BattMonitor &battery) const;
|
2017-05-29 14:03:43 -03:00
|
|
|
void send_distance_sensor(const RangeFinder &rangefinder, const uint8_t instance) const;
|
|
|
|
bool send_distance_sensor(const RangeFinder &rangefinder) const;
|
2017-05-30 07:33:03 -03:00
|
|
|
void send_distance_sensor_downward(const RangeFinder &rangefinder) const;
|
2017-06-05 15:49:34 -03:00
|
|
|
void send_rangefinder_downward(const RangeFinder &rangefinder) const;
|
2014-01-03 20:30:32 -04:00
|
|
|
void send_ahrs2(AP_AHRS &ahrs);
|
2014-06-27 21:50:17 -03:00
|
|
|
bool send_gps_raw(AP_GPS &gps);
|
2014-05-27 20:35:30 -03:00
|
|
|
void send_system_time(AP_GPS &gps);
|
2014-08-16 08:31:14 -03:00
|
|
|
void send_radio_in(uint8_t receiver_rssi);
|
2014-07-13 02:31:25 -03:00
|
|
|
void send_raw_imu(const AP_InertialSensor &ins, const Compass &compass);
|
|
|
|
void send_scaled_pressure(AP_Baro &barometer);
|
|
|
|
void send_sensor_offsets(const AP_InertialSensor &ins, const Compass &compass, AP_Baro &barometer);
|
|
|
|
void send_ahrs(AP_AHRS &ahrs);
|
2014-08-08 23:14:06 -03:00
|
|
|
void send_battery2(const AP_BattMonitor &battery);
|
2015-01-03 00:53:22 -04:00
|
|
|
#if AP_AHRS_NAVEKF_AVAILABLE
|
|
|
|
void send_opticalflow(AP_AHRS_NavEKF &ahrs, const OpticalFlow &optflow);
|
|
|
|
#endif
|
2015-08-21 14:49:01 -03:00
|
|
|
void send_autopilot_version(uint8_t major_version, uint8_t minor_version, uint8_t patch_version, uint8_t version_type) const;
|
2015-04-05 12:24:05 -03:00
|
|
|
void send_local_position(const AP_AHRS &ahrs) const;
|
2015-06-12 03:35:31 -03:00
|
|
|
void send_vibration(const AP_InertialSensor &ins) const;
|
2015-10-02 05:55:57 -03:00
|
|
|
void send_home(const Location &home) const;
|
|
|
|
static void send_home_all(const Location &home);
|
2016-05-16 19:36:49 -03:00
|
|
|
void send_heartbeat(uint8_t type, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status);
|
2016-07-15 07:04:19 -03:00
|
|
|
void send_servo_output_raw(bool hil);
|
2016-05-11 03:19:15 -03:00
|
|
|
static void send_collision_all(const AP_Avoidance::Obstacle &threat, MAV_COLLISION_ACTION behaviour);
|
2017-05-29 18:03:10 -03:00
|
|
|
void send_accelcal_vehicle_position(uint32_t position);
|
2013-12-28 01:00:19 -04:00
|
|
|
|
2014-07-17 08:03:12 -03:00
|
|
|
// return a bitmap of active channels. Used by libraries to loop
|
|
|
|
// over active channels to send to all active channels
|
|
|
|
static uint8_t active_channel_mask(void) { return mavlink_active; }
|
|
|
|
|
2016-05-30 07:05:00 -03:00
|
|
|
// return a bitmap of streaming channels
|
|
|
|
static uint8_t streaming_channel_mask(void) { return chan_is_streaming; }
|
|
|
|
|
2014-08-08 00:45:06 -03:00
|
|
|
/*
|
2016-02-23 16:50:57 -04:00
|
|
|
send a statustext message to active MAVLink connections, or a specific
|
|
|
|
one. This function is static so it can be called from any library.
|
2014-08-08 00:45:06 -03:00
|
|
|
*/
|
2015-10-26 08:25:44 -03:00
|
|
|
static void send_statustext_all(MAV_SEVERITY severity, const char *fmt, ...);
|
2016-02-23 16:50:57 -04:00
|
|
|
static void send_statustext_chan(MAV_SEVERITY severity, uint8_t dest_chan, const char *fmt, ...);
|
2014-08-08 00:45:06 -03:00
|
|
|
|
2015-10-06 06:54:05 -03:00
|
|
|
// send a PARAM_VALUE message to all active MAVLink connections.
|
|
|
|
static void send_parameter_value_all(const char *param_name, ap_var_type param_type, float param_value);
|
2017-04-29 01:36:59 -03:00
|
|
|
|
|
|
|
// send queued parameters if needed
|
|
|
|
void send_queued_parameters(void);
|
2015-10-06 06:54:05 -03:00
|
|
|
|
2015-03-28 22:36:06 -03:00
|
|
|
/*
|
|
|
|
send a MAVLink message to all components with this vehicle's system id
|
|
|
|
This is a no-op if no routes to components have been learned
|
|
|
|
*/
|
|
|
|
static void send_to_components(const mavlink_message_t* msg) { routing.send_to_components(msg); }
|
2016-05-11 06:24:59 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
allow forwarding of packets / heartbeats to be blocked as required by some components to reduce traffic
|
|
|
|
*/
|
|
|
|
static void disable_channel_routing(mavlink_channel_t chan) { routing.no_route_mask |= (1U<<(chan-MAVLINK_COMM_0)); }
|
|
|
|
|
2015-07-24 08:52:56 -03:00
|
|
|
/*
|
|
|
|
search for a component in the routing table with given mav_type and retrieve it's sysid, compid and channel
|
|
|
|
returns if a matching component is found
|
|
|
|
*/
|
|
|
|
static bool find_by_mavtype(uint8_t mav_type, uint8_t &sysid, uint8_t &compid, mavlink_channel_t &channel) { return routing.find_by_mavtype(mav_type, sysid, compid, channel); }
|
|
|
|
|
2016-01-21 02:55:50 -04:00
|
|
|
// update signing timestamp on GPS lock
|
|
|
|
static void update_signing_timestamp(uint64_t timestamp_usec);
|
2016-04-05 01:09:47 -03:00
|
|
|
|
|
|
|
// return current packet overhead for a channel
|
|
|
|
static uint8_t packet_overhead_chan(mavlink_channel_t chan);
|
|
|
|
|
2016-05-29 20:54:11 -03:00
|
|
|
// FIXME: move this to be private/protected once possible
|
|
|
|
bool telemetry_delayed(mavlink_channel_t chan);
|
|
|
|
virtual uint32_t telem_delay() const = 0;
|
|
|
|
|
2016-05-27 09:52:24 -03:00
|
|
|
protected:
|
|
|
|
|
2016-08-13 18:42:40 -03:00
|
|
|
// overridable method to check for packet acceptance. Allows for
|
|
|
|
// enforcement of GCS sysid
|
|
|
|
virtual bool accept_packet(const mavlink_status_t &status, mavlink_message_t &msg) { return true; }
|
|
|
|
|
2016-05-27 09:52:24 -03:00
|
|
|
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);
|
|
|
|
|
2016-11-06 20:03:11 -04:00
|
|
|
void handle_common_message(mavlink_message_t *msg);
|
2016-05-27 09:52:24 -03:00
|
|
|
void handle_log_message(mavlink_message_t *msg, DataFlash_Class &dataflash);
|
|
|
|
void handle_setup_signing(const mavlink_message_t *msg);
|
2016-08-11 00:17:32 -03:00
|
|
|
uint8_t handle_preflight_reboot(const mavlink_command_long_t &packet, bool disable_overrides);
|
2016-10-15 05:51:17 -03:00
|
|
|
uint8_t handle_rc_bind(const mavlink_command_long_t &packet);
|
2016-11-06 21:42:47 -04:00
|
|
|
|
|
|
|
void handle_device_op_read(mavlink_message_t *msg);
|
|
|
|
void handle_device_op_write(mavlink_message_t *msg);
|
2017-03-29 03:47:32 -03:00
|
|
|
|
|
|
|
void handle_timesync(mavlink_message_t *msg);
|
2016-11-06 20:03:11 -04:00
|
|
|
|
2011-02-17 05:36:33 -04:00
|
|
|
private:
|
2016-05-29 07:47:57 -03:00
|
|
|
|
|
|
|
float adjust_rate_for_stream_trigger(enum streams stream_num);
|
2016-05-05 17:45:37 -03:00
|
|
|
|
2016-05-27 09:52:24 -03:00
|
|
|
virtual void handleMessage(mavlink_message_t * msg) = 0;
|
2012-08-16 21:50:03 -03:00
|
|
|
|
2014-12-09 23:39:32 -04:00
|
|
|
/// The stream we are communicating over
|
|
|
|
AP_HAL::UARTDriver *_port;
|
|
|
|
|
2012-08-16 21:50:03 -03:00
|
|
|
/// Perform queued sending operations
|
|
|
|
///
|
|
|
|
enum ap_var_type _queued_parameter_type; ///< type of the next
|
|
|
|
// parameter
|
|
|
|
AP_Param::ParamToken _queued_parameter_token; ///AP_Param token for
|
|
|
|
// next() call
|
|
|
|
uint16_t _queued_parameter_index; ///< next queued
|
|
|
|
// parameter's index
|
|
|
|
uint16_t _queued_parameter_count; ///< saved count of
|
|
|
|
// parameters for
|
|
|
|
// queued send
|
2013-11-23 06:45:42 -04:00
|
|
|
uint32_t _queued_parameter_send_time_ms;
|
2012-08-16 21:50:03 -03:00
|
|
|
|
|
|
|
/// Count the number of reportable parameters.
|
|
|
|
///
|
|
|
|
/// Not all parameters can be reported via MAVlink. We count the number
|
|
|
|
// that are
|
|
|
|
/// so that we can report to a GCS the number of parameters it should
|
|
|
|
// expect when it
|
|
|
|
/// requests the full set.
|
|
|
|
///
|
|
|
|
/// @return The number of reportable parameters.
|
|
|
|
///
|
|
|
|
uint16_t packet_drops;
|
2011-04-15 10:24:05 -03:00
|
|
|
|
2011-10-27 04:35:25 -03:00
|
|
|
// this allows us to detect the user wanting the CLI to start
|
2012-08-16 21:50:03 -03:00
|
|
|
uint8_t crlf_count;
|
2011-10-27 04:35:25 -03:00
|
|
|
|
2012-08-16 21:50:03 -03:00
|
|
|
// waypoints
|
|
|
|
uint16_t waypoint_dest_sysid; // where to send requests
|
|
|
|
uint16_t waypoint_dest_compid; // "
|
|
|
|
uint16_t waypoint_count;
|
|
|
|
uint32_t waypoint_timelast_receive; // milliseconds
|
|
|
|
uint32_t waypoint_timelast_request; // milliseconds
|
2016-01-20 02:20:30 -04:00
|
|
|
const uint16_t waypoint_receive_timeout = 8000; // milliseconds
|
2012-08-16 21:50:03 -03:00
|
|
|
|
2012-04-01 22:18:42 -03:00
|
|
|
// number of 50Hz ticks until we next send this stream
|
2012-08-16 21:50:03 -03:00
|
|
|
uint8_t stream_ticks[NUM_STREAMS];
|
2012-04-01 22:18:42 -03:00
|
|
|
|
|
|
|
// number of extra ticks to add to slow things down for the radio
|
2012-08-16 21:50:03 -03:00
|
|
|
uint8_t stream_slowdown;
|
2013-03-20 23:54:04 -03:00
|
|
|
|
|
|
|
// millis value to calculate cli timeout relative to.
|
|
|
|
// exists so we can separate the cli entry time from the system start time
|
|
|
|
uint32_t _cli_timeout;
|
2013-12-15 03:57:15 -04:00
|
|
|
|
|
|
|
uint8_t _log_listing:1; // sending log list
|
|
|
|
uint8_t _log_sending:1; // sending log data
|
|
|
|
|
|
|
|
// next log list entry to send
|
|
|
|
uint16_t _log_next_list_entry;
|
|
|
|
|
|
|
|
// last log list entry to send
|
|
|
|
uint16_t _log_last_list_entry;
|
|
|
|
|
|
|
|
// number of log files
|
|
|
|
uint16_t _log_num_logs;
|
|
|
|
|
|
|
|
// log number for data send
|
|
|
|
uint16_t _log_num_data;
|
|
|
|
|
|
|
|
// offset in log
|
|
|
|
uint32_t _log_data_offset;
|
|
|
|
|
2013-12-29 00:00:04 -04:00
|
|
|
// size of log file
|
|
|
|
uint32_t _log_data_size;
|
|
|
|
|
2013-12-15 03:57:15 -04:00
|
|
|
// number of bytes left to send
|
|
|
|
uint32_t _log_data_remaining;
|
|
|
|
|
|
|
|
// start page of log data
|
|
|
|
uint16_t _log_data_page;
|
|
|
|
|
2017-04-28 01:35:53 -03:00
|
|
|
// perf counters
|
|
|
|
static AP_HAL::Util::perf_counter_t _perf_packet;
|
|
|
|
static AP_HAL::Util::perf_counter_t _perf_update;
|
|
|
|
|
2014-03-18 20:56:09 -03:00
|
|
|
// deferred message handling
|
|
|
|
enum ap_message deferred_messages[MSG_RETRY_DEFERRED];
|
|
|
|
uint8_t next_deferred_message;
|
|
|
|
uint8_t num_deferred_messages;
|
|
|
|
|
2016-05-27 21:41:52 -03:00
|
|
|
// time when we missed sending a parameter for GCS
|
|
|
|
static uint32_t reserve_param_space_start_ms;
|
|
|
|
|
2014-07-17 08:03:12 -03:00
|
|
|
// bitmask of what mavlink channels are active
|
|
|
|
static uint8_t mavlink_active;
|
2014-05-20 23:38:07 -03:00
|
|
|
|
2016-06-13 17:36:34 -03:00
|
|
|
// bitmask of what mavlink channels are streaming
|
|
|
|
static uint8_t chan_is_streaming;
|
|
|
|
|
2014-12-09 23:31:31 -04:00
|
|
|
// mavlink routing object
|
|
|
|
static MAVLink_routing routing;
|
|
|
|
|
2016-10-26 19:06:54 -03:00
|
|
|
// pointer to static frsky_telem for queueing of text messages
|
|
|
|
static AP_Frsky_Telem *frsky_telemetry_p;
|
|
|
|
|
2016-05-16 01:05:09 -03:00
|
|
|
static const AP_SerialManager *serialmanager_p;
|
|
|
|
|
2017-04-29 02:30:57 -03:00
|
|
|
struct pending_param_request {
|
|
|
|
mavlink_channel_t chan;
|
|
|
|
int16_t param_index;
|
|
|
|
char param_name[AP_MAX_NAME_SIZE+1];
|
|
|
|
};
|
|
|
|
|
|
|
|
struct pending_param_reply {
|
|
|
|
mavlink_channel_t chan;
|
|
|
|
float value;
|
|
|
|
enum ap_var_type p_type;
|
|
|
|
int16_t param_index;
|
|
|
|
uint16_t count;
|
|
|
|
char param_name[AP_MAX_NAME_SIZE+1];
|
|
|
|
};
|
|
|
|
|
|
|
|
// queue of pending parameter requests and replies
|
|
|
|
static ObjectBuffer<pending_param_request> param_requests;
|
|
|
|
static ObjectBuffer<pending_param_reply> param_replies;
|
|
|
|
|
|
|
|
// have we registered the IO timer callback?
|
|
|
|
static bool param_timer_registered;
|
|
|
|
|
|
|
|
// IO timer callback for parameters
|
|
|
|
void param_io_timer(void);
|
|
|
|
|
|
|
|
// send an async parameter reply
|
|
|
|
void send_parameter_reply(void);
|
|
|
|
|
|
|
|
|
2014-12-09 23:31:31 -04:00
|
|
|
// a vehicle can optionally snoop on messages for other systems
|
|
|
|
static void (*msg_snoop)(const mavlink_message_t* msg);
|
|
|
|
|
2014-03-18 20:56:09 -03:00
|
|
|
// vehicle specific message send function
|
2016-05-27 09:52:24 -03:00
|
|
|
virtual bool try_send_message(enum ap_message id) = 0;
|
2014-03-18 20:56:09 -03:00
|
|
|
|
2016-05-27 09:52:24 -03:00
|
|
|
virtual bool handle_guided_request(AP_Mission::Mission_Command &cmd) = 0;
|
|
|
|
virtual void handle_change_alt_request(AP_Mission::Mission_Command &cmd) = 0;
|
2014-03-18 19:59:40 -03:00
|
|
|
|
2013-12-15 03:57:15 -04:00
|
|
|
void handle_log_request_list(mavlink_message_t *msg, DataFlash_Class &dataflash);
|
|
|
|
void handle_log_request_data(mavlink_message_t *msg, DataFlash_Class &dataflash);
|
2014-09-26 23:43:14 -03:00
|
|
|
void handle_log_request_erase(mavlink_message_t *msg, DataFlash_Class &dataflash);
|
|
|
|
void handle_log_request_end(mavlink_message_t *msg, DataFlash_Class &dataflash);
|
2013-12-15 03:57:15 -04:00
|
|
|
void handle_log_send_listing(DataFlash_Class &dataflash);
|
2013-12-27 23:25:07 -04:00
|
|
|
bool handle_log_send_data(DataFlash_Class &dataflash);
|
2014-03-17 23:52:07 -03:00
|
|
|
|
2014-03-18 16:43:22 -03:00
|
|
|
|
2014-04-03 23:55:18 -03:00
|
|
|
void lock_channel(mavlink_channel_t chan, bool lock);
|
2015-04-22 20:11:43 -03:00
|
|
|
|
2014-03-18 16:43:22 -03:00
|
|
|
// return true if this channel has hardware flow control
|
|
|
|
bool have_flow_control(void);
|
2016-01-20 22:49:06 -04:00
|
|
|
|
2016-01-21 02:55:50 -04:00
|
|
|
mavlink_signing_t signing;
|
|
|
|
static mavlink_signing_streams_t signing_streams;
|
2016-04-05 20:38:21 -03:00
|
|
|
static uint32_t last_signing_save_ms;
|
2016-01-21 02:55:50 -04:00
|
|
|
|
|
|
|
static StorageAccess _signing_storage;
|
2016-04-05 20:38:21 -03:00
|
|
|
static bool signing_key_save(const struct SigningKey &key);
|
|
|
|
static bool signing_key_load(struct SigningKey &key);
|
2016-01-20 22:49:06 -04:00
|
|
|
void load_signing_key(void);
|
2016-04-05 01:09:47 -03:00
|
|
|
bool signing_enabled(void) const;
|
2016-04-05 20:38:21 -03:00
|
|
|
static void save_signing_timestamp(bool force_save_now);
|
2011-02-17 05:36:33 -04:00
|
|
|
};
|
2016-05-30 07:05:00 -03:00
|
|
|
|
|
|
|
/// @class GCS
|
|
|
|
/// @brief global GCS object
|
|
|
|
class GCS
|
|
|
|
{
|
|
|
|
|
|
|
|
public:
|
|
|
|
|
|
|
|
GCS() {
|
|
|
|
if (_singleton == nullptr) {
|
|
|
|
_singleton = this;
|
|
|
|
} else {
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
|
|
|
// this is a serious problem, but we don't need to kill a
|
|
|
|
// real vehicle
|
|
|
|
AP_HAL::panic("GCS must be singleton");
|
|
|
|
#endif
|
|
|
|
}
|
|
|
|
};
|
|
|
|
|
|
|
|
static class GCS *instance() {
|
|
|
|
return _singleton;
|
|
|
|
}
|
|
|
|
|
2017-02-23 02:28:32 -04:00
|
|
|
virtual void send_statustext(MAV_SEVERITY severity, uint8_t dest_bitmask, const char *text);
|
2016-05-30 07:05:00 -03:00
|
|
|
void service_statustext(void);
|
|
|
|
|
|
|
|
/*
|
|
|
|
set a dataflash pointer for logging
|
|
|
|
*/
|
|
|
|
void set_dataflash(DataFlash_Class *dataflash) {
|
|
|
|
dataflash_p = dataflash;
|
|
|
|
}
|
|
|
|
|
|
|
|
// pointer to static dataflash for logging of text messages
|
|
|
|
DataFlash_Class *dataflash_p;
|
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
set a frsky_telem pointer for queueing
|
|
|
|
*/
|
|
|
|
void register_frsky_telemetry_callback(AP_Frsky_Telem *frsky_telemetry) {
|
|
|
|
frsky_telemetry_p = frsky_telemetry;
|
|
|
|
}
|
|
|
|
|
|
|
|
// static frsky_telem pointer to support queueing text messages
|
|
|
|
AP_Frsky_Telem *frsky_telemetry_p;
|
|
|
|
|
|
|
|
private:
|
|
|
|
|
|
|
|
static GCS *_singleton;
|
|
|
|
|
|
|
|
struct statustext_t {
|
|
|
|
uint8_t bitmask;
|
|
|
|
mavlink_statustext_t msg;
|
|
|
|
};
|
|
|
|
|
|
|
|
#if HAL_CPU_CLASS <= HAL_CPU_CLASS_150 || CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
|
|
|
static const uint8_t _status_capacity = 5;
|
|
|
|
#else
|
|
|
|
static const uint8_t _status_capacity = 30;
|
|
|
|
#endif
|
|
|
|
|
|
|
|
ObjectArray<statustext_t> _statustext_queue{_status_capacity};
|
|
|
|
|
|
|
|
};
|
|
|
|
|
|
|
|
GCS &gcs();
|