2011-03-19 07:20:11 -03:00
|
|
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
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.
|
2011-02-17 05:36:33 -04:00
|
|
|
|
|
|
|
#ifndef __GCS_H
|
|
|
|
#define __GCS_H
|
|
|
|
|
2012-12-12 19:46:20 -04:00
|
|
|
#include <AP_HAL.h>
|
2013-11-23 06:45:42 -04:00
|
|
|
#include <AP_Common.h>
|
2013-12-15 03:57:15 -04:00
|
|
|
#include <GCS_MAVLink.h>
|
|
|
|
#include <DataFlash.h>
|
2014-03-17 23:52:07 -03:00
|
|
|
#include <AP_Mission.h>
|
2013-11-23 06:45:42 -04:00
|
|
|
#include <stdint.h>
|
2011-02-17 05:36:33 -04:00
|
|
|
|
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,
|
|
|
|
MSG_RADIO_OUT,
|
|
|
|
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,
|
|
|
|
MSG_RETRY_DEFERRED // this must be last
|
|
|
|
};
|
|
|
|
|
|
|
|
|
2011-02-17 05:36:33 -04:00
|
|
|
///
|
|
|
|
/// @class GCS
|
|
|
|
/// @brief Class describing the interface between the APM code
|
|
|
|
/// proper and the GCS implementation.
|
|
|
|
///
|
|
|
|
/// GCS' are currently implemented inside the sketch and as such have
|
|
|
|
/// access to all global state. The sketch should not, however, call GCS
|
|
|
|
/// internal functions - all calls to the GCS should be routed through
|
|
|
|
/// this interface (or functions explicitly exposed by a subclass).
|
|
|
|
///
|
|
|
|
class GCS_Class
|
|
|
|
{
|
|
|
|
public:
|
|
|
|
|
2012-08-16 21:50:03 -03:00
|
|
|
/// Startup initialisation.
|
|
|
|
///
|
|
|
|
/// This routine performs any one-off initialisation required before
|
|
|
|
/// GCS messages are exchanged.
|
|
|
|
///
|
|
|
|
/// @note The stream is expected to be set up and configured for the
|
|
|
|
/// correct bitrate before ::init is called.
|
|
|
|
///
|
|
|
|
/// @note The stream is currently BetterStream so that we can use the _P
|
|
|
|
/// methods; this may change if Arduino adds them to Print.
|
|
|
|
///
|
|
|
|
/// @param port The stream over which messages are exchanged.
|
|
|
|
///
|
2012-12-12 19:46:20 -04:00
|
|
|
void init(AP_HAL::UARTDriver *port) {
|
2011-11-20 05:42:51 -04:00
|
|
|
_port = port;
|
|
|
|
}
|
2011-02-17 05:36:33 -04:00
|
|
|
|
2012-08-16 21:50:03 -03:00
|
|
|
/// Update GCS state.
|
|
|
|
///
|
|
|
|
/// This may involve checking for received bytes on the stream,
|
|
|
|
/// or sending additional periodic messages.
|
|
|
|
void update(void) {
|
|
|
|
}
|
|
|
|
|
|
|
|
/// Send a message with a single numeric parameter.
|
|
|
|
///
|
|
|
|
/// This may be a standalone message, or the GCS driver may
|
|
|
|
/// have its own way of locating additional parameters to send.
|
|
|
|
///
|
|
|
|
/// @param id ID of the message to send.
|
|
|
|
/// @param param Explicit message parameter.
|
|
|
|
///
|
|
|
|
void send_message(enum ap_message id) {
|
|
|
|
}
|
|
|
|
|
2013-11-23 06:45:42 -04:00
|
|
|
/// Send a text message.
|
|
|
|
///
|
|
|
|
/// @param severity A value describing the importance of the message.
|
|
|
|
/// @param str The text to be sent.
|
|
|
|
///
|
|
|
|
void send_text(gcs_severity severity, const char *str) {
|
|
|
|
}
|
|
|
|
|
2012-08-16 21:50:03 -03:00
|
|
|
/// Send a text message with a PSTR()
|
|
|
|
///
|
|
|
|
/// @param severity A value describing the importance of the message.
|
|
|
|
/// @param str The text to be sent.
|
|
|
|
///
|
2012-12-18 06:15:11 -04:00
|
|
|
void send_text_P(gcs_severity severity, const prog_char_t *str) {
|
2012-08-16 21:50:03 -03:00
|
|
|
}
|
2011-02-17 05:36:33 -04:00
|
|
|
|
|
|
|
// send streams which match frequency range
|
2012-08-16 21:50:03 -03:00
|
|
|
void data_stream_send(void);
|
2011-02-17 05:36:33 -04:00
|
|
|
|
2011-11-20 05:42:51 -04:00
|
|
|
// set to true if this GCS link is active
|
2012-08-16 21:50:03 -03:00
|
|
|
bool initialised;
|
2011-11-20 05:42:51 -04:00
|
|
|
|
2011-02-17 05:36:33 -04:00
|
|
|
protected:
|
2012-08-16 21:50:03 -03:00
|
|
|
/// The stream we are communicating over
|
2012-12-12 19:46:20 -04:00
|
|
|
AP_HAL::UARTDriver * _port;
|
2011-02-17 05:36:33 -04:00
|
|
|
};
|
|
|
|
|
2013-12-15 03:57:15 -04:00
|
|
|
|
2011-02-17 05:36:33 -04:00
|
|
|
//
|
|
|
|
// GCS class definitions.
|
|
|
|
//
|
|
|
|
// These are here so that we can declare the GCS object early in the sketch
|
|
|
|
// and then reference it statically rather than via a pointer.
|
|
|
|
//
|
|
|
|
|
|
|
|
///
|
|
|
|
/// @class GCS_MAVLINK
|
|
|
|
/// @brief The mavlink protocol for qgroundcontrol
|
|
|
|
///
|
|
|
|
class GCS_MAVLINK : public GCS_Class
|
|
|
|
{
|
|
|
|
public:
|
2012-08-16 21:50:03 -03:00
|
|
|
GCS_MAVLINK();
|
|
|
|
void update(void);
|
2012-12-12 19:46:20 -04:00
|
|
|
void init(AP_HAL::UARTDriver *port);
|
2012-08-16 21:50:03 -03:00
|
|
|
void send_message(enum ap_message id);
|
|
|
|
void send_text(gcs_severity severity, const char *str);
|
2012-12-18 06:15:11 -04:00
|
|
|
void send_text_P(gcs_severity severity, const prog_char_t *str);
|
2012-08-16 21:50:03 -03:00
|
|
|
void data_stream_send(void);
|
|
|
|
void queued_param_send();
|
|
|
|
void queued_waypoint_send();
|
|
|
|
|
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
2012-02-12 07:27:03 -04:00
|
|
|
|
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,
|
|
|
|
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-11-23 06:45:42 -04:00
|
|
|
// this costs us 51 bytes per instance, but means that low priority
|
|
|
|
// messages don't block the CPU
|
|
|
|
mavlink_statustext_t pending_status;
|
|
|
|
|
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;
|
|
|
|
|
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);
|
2014-01-03 20:30:32 -04:00
|
|
|
void send_ahrs2(AP_AHRS &ahrs);
|
2013-12-28 01:00:19 -04:00
|
|
|
|
2011-02-17 05:36:33 -04:00
|
|
|
private:
|
2012-08-16 21:50:03 -03:00
|
|
|
void handleMessage(mavlink_message_t * msg);
|
|
|
|
|
|
|
|
/// 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
|
|
|
|
// 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 _count_parameters(); ///< count reportable
|
|
|
|
// parameters
|
|
|
|
|
|
|
|
uint16_t _parameter_count; ///< cache of reportable
|
|
|
|
// parameters
|
|
|
|
|
|
|
|
mavlink_channel_t chan;
|
|
|
|
uint16_t packet_drops;
|
2011-04-15 10:24:05 -03:00
|
|
|
|
2011-10-27 04:35:25 -03:00
|
|
|
#if CLI_ENABLED == ENABLED
|
|
|
|
// 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
|
|
|
#endif
|
|
|
|
|
2012-08-16 21:50:03 -03:00
|
|
|
// waypoints
|
|
|
|
uint16_t waypoint_request_i; // request index
|
2013-05-29 03:25:05 -03:00
|
|
|
uint16_t waypoint_request_last; // last request index
|
2012-08-16 21:50:03 -03:00
|
|
|
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
|
2013-12-15 03:57:15 -04:00
|
|
|
const uint16_t waypoint_receive_timeout; // milliseconds
|
2012-08-16 21:50:03 -03:00
|
|
|
|
2013-11-23 06:45:42 -04:00
|
|
|
// saveable rate of each stream
|
|
|
|
AP_Int16 streamRates[NUM_STREAMS];
|
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;
|
|
|
|
|
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;
|
|
|
|
|
|
|
|
// vehicle specific message send function
|
|
|
|
bool try_send_message(enum ap_message id);
|
|
|
|
|
2014-03-18 19:59:40 -03:00
|
|
|
void handle_guided_request(AP_Mission::Mission_Command &cmd);
|
|
|
|
void handle_change_alt_request(AP_Mission::Mission_Command &cmd);
|
|
|
|
|
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);
|
|
|
|
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);
|
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 10:30:59 -03:00
|
|
|
void handle_mission_request_list(AP_Mission &mission, mavlink_message_t *msg);
|
2014-03-18 19:59:40 -03:00
|
|
|
void handle_mission_request(AP_Mission &mission, mavlink_message_t *msg);
|
2014-03-18 16:43:22 -03:00
|
|
|
|
2014-03-18 10:30:59 -03:00
|
|
|
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);
|
2014-03-18 19:59:40 -03:00
|
|
|
void handle_mission_item(mavlink_message_t *msg, AP_Mission &mission);
|
2014-03-18 16:43:22 -03:00
|
|
|
|
2014-03-18 19:01:51 -03:00
|
|
|
void handle_request_data_stream(mavlink_message_t *msg, bool save);
|
2014-03-18 18:34:16 -03:00
|
|
|
void handle_param_request_list(mavlink_message_t *msg);
|
|
|
|
void handle_param_request_read(mavlink_message_t *msg);
|
2014-03-18 19:22:04 -03:00
|
|
|
void handle_param_set(mavlink_message_t *msg, DataFlash_Class *DataFlash);
|
2014-03-19 19:55:04 -03:00
|
|
|
void handle_radio_status(mavlink_message_t *msg, DataFlash_Class &dataflash, bool log_radio);
|
2014-04-03 23:55:18 -03:00
|
|
|
void handle_serial_control(mavlink_message_t *msg, AP_GPS &gps);
|
|
|
|
void lock_channel(mavlink_channel_t chan, bool lock);
|
2014-03-18 18:34:16 -03:00
|
|
|
|
2014-03-18 16:43:22 -03:00
|
|
|
// return true if this channel has hardware flow control
|
|
|
|
bool have_flow_control(void);
|
2011-02-17 05:36:33 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
#endif // __GCS_H
|