Browse Source

uncrustify ArduPlane/GCS.h

mission-4.1.18
uncrustify 13 years ago committed by Pat Hickey
parent
commit
bd0146f776
  1. 239
      ArduPlane/GCS.h

239
ArduPlane/GCS.h

@ -1,7 +1,8 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/// @file GCS.h /// @file GCS.h
/// @brief Interface definition for the various Ground Control System protocols. /// @brief Interface definition for the various Ground Control System
// protocols.
#ifndef __GCS_H #ifndef __GCS_H
#define __GCS_H #define __GCS_H
@ -26,67 +27,71 @@ class GCS_Class
{ {
public: public:
/// Startup initialisation. /// Startup initialisation.
/// ///
/// This routine performs any one-off initialisation required before /// This routine performs any one-off initialisation required before
/// GCS messages are exchanged. /// GCS messages are exchanged.
/// ///
/// @note The stream is expected to be set up and configured for the /// @note The stream is expected to be set up and configured for the
/// correct bitrate before ::init is called. /// correct bitrate before ::init is called.
/// ///
/// @note The stream is currently BetterStream so that we can use the _P /// @note The stream is currently BetterStream so that we can use the _P
/// methods; this may change if Arduino adds them to Print. /// methods; this may change if Arduino adds them to Print.
/// ///
/// @param port The stream over which messages are exchanged. /// @param port The stream over which messages are exchanged.
/// ///
void init(FastSerial *port) { void init(FastSerial *port) {
_port = port; _port = port;
initialised = true; initialised = true;
last_gps_satellites = 255; last_gps_satellites = 255;
} }
/// Update GCS state. /// Update GCS state.
/// ///
/// This may involve checking for received bytes on the stream, /// This may involve checking for received bytes on the stream,
/// or sending additional periodic messages. /// or sending additional periodic messages.
void update(void) {} void update(void) {
}
/// Send a message with a single numeric parameter.
/// /// 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. /// 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. /// @param id ID of the message to send.
/// /// @param param Explicit message parameter.
void send_message(enum ap_message id) {} ///
void send_message(enum ap_message id) {
/// Send a text message. }
///
/// @param severity A value describing the importance of the message. /// Send a text message.
/// @param str The text to be sent. ///
/// /// @param severity A value describing the importance of the message.
void send_text(gcs_severity severity, const char *str) {} /// @param str The text to be sent.
///
/// Send a text message with a PSTR() void send_text(gcs_severity severity, const char *str) {
/// }
/// @param severity A value describing the importance of the message.
/// @param str The text to be sent. /// Send a text message with a PSTR()
/// ///
void send_text(gcs_severity severity, const prog_char_t *str) {} /// @param severity A value describing the importance of the message.
/// @param str The text to be sent.
///
void send_text(gcs_severity severity, const prog_char_t *str) {
}
// send streams which match frequency range // send streams which match frequency range
void data_stream_send(void); void data_stream_send(void);
// set to true if this GCS link is active // set to true if this GCS link is active
bool initialised; bool initialised;
// used to prevent wasting bandwidth with GPS_STATUS messages // used to prevent wasting bandwidth with GPS_STATUS messages
uint8_t last_gps_satellites; uint8_t last_gps_satellites;
protected: protected:
/// The stream we are communicating over /// The stream we are communicating over
FastSerial *_port; FastSerial * _port;
}; };
// //
@ -103,17 +108,17 @@ protected:
class GCS_MAVLINK : public GCS_Class class GCS_MAVLINK : public GCS_Class
{ {
public: public:
GCS_MAVLINK(); GCS_MAVLINK();
void update(void); void update(void);
void init(FastSerial *port); void init(FastSerial *port);
void send_message(enum ap_message id); void send_message(enum ap_message id);
void send_text(gcs_severity severity, const char *str); void send_text(gcs_severity severity, const char *str);
void send_text(gcs_severity severity, const prog_char_t *str); void send_text(gcs_severity severity, const prog_char_t *str);
void data_stream_send(void); void data_stream_send(void);
void queued_param_send(); void queued_param_send();
void queued_waypoint_send(); void queued_waypoint_send();
static const struct AP_Param::GroupInfo var_info[]; static const struct AP_Param::GroupInfo var_info[];
// NOTE! The streams enum below and the // NOTE! The streams enum below and the
// set of AP_Int16 stream rates _must_ be // set of AP_Int16 stream rates _must_ be
@ -130,70 +135,80 @@ public:
NUM_STREAMS}; NUM_STREAMS};
// see if we should send a stream now. Called at 50Hz // see if we should send a stream now. Called at 50Hz
bool stream_trigger(enum streams stream_num); bool stream_trigger(enum streams stream_num);
private: private:
void handleMessage(mavlink_message_t * msg); void handleMessage(mavlink_message_t * msg);
/// Perform queued sending operations /// Perform queued sending operations
/// ///
AP_Param *_queued_parameter; ///< next parameter to be sent in queue AP_Param * _queued_parameter; ///< next parameter to
enum ap_var_type _queued_parameter_type; ///< type of the next parameter // be sent in queue
AP_Param::ParamToken _queued_parameter_token;///AP_Param token for next() call enum ap_var_type _queued_parameter_type; ///< type of the next
uint16_t _queued_parameter_index; ///< next queued parameter's index // parameter
uint16_t _queued_parameter_count; ///< saved count of parameters for queued send AP_Param::ParamToken _queued_parameter_token; ///AP_Param token for
// next() call
/// Count the number of reportable parameters. uint16_t _queued_parameter_index; ///< next queued
/// // parameter's index
/// Not all parameters can be reported via MAVlink. We count the number that are uint16_t _queued_parameter_count; ///< saved count of
/// so that we can report to a GCS the number of parameters it should expect when it // parameters for
/// requests the full set. // queued send
///
/// @return The number of reportable parameters. /// Count the number of reportable parameters.
/// ///
uint16_t _count_parameters(); ///< count reportable parameters /// Not all parameters can be reported via MAVlink. We count the number
// that are
uint16_t _parameter_count; ///< cache of reportable parameters /// so that we can report to a GCS the number of parameters it should
// expect when it
mavlink_channel_t chan; /// requests the full set.
uint16_t packet_drops; ///
/// @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;
#if CLI_ENABLED == ENABLED #if CLI_ENABLED == ENABLED
// this allows us to detect the user wanting the CLI to start // this allows us to detect the user wanting the CLI to start
uint8_t crlf_count; uint8_t crlf_count;
#endif #endif
// waypoints // waypoints
uint16_t waypoint_request_i; // request index uint16_t waypoint_request_i; // request index
uint16_t waypoint_request_last; // last request index uint16_t waypoint_request_last; // last request index
uint16_t waypoint_dest_sysid; // where to send requests uint16_t waypoint_dest_sysid; // where to send requests
uint16_t waypoint_dest_compid; // " uint16_t waypoint_dest_compid; // "
bool waypoint_sending; // currently in send process bool waypoint_sending; // currently in send process
bool waypoint_receiving; // currently receiving bool waypoint_receiving; // currently receiving
uint16_t waypoint_count; uint16_t waypoint_count;
uint32_t waypoint_timelast_send; // milliseconds uint32_t waypoint_timelast_send; // milliseconds
uint32_t waypoint_timelast_receive; // milliseconds uint32_t waypoint_timelast_receive; // milliseconds
uint32_t waypoint_timelast_request; // milliseconds uint32_t waypoint_timelast_request; // milliseconds
uint16_t waypoint_send_timeout; // milliseconds uint16_t waypoint_send_timeout; // milliseconds
uint16_t waypoint_receive_timeout; // milliseconds uint16_t waypoint_receive_timeout; // milliseconds
// data stream rates. The code assumes that // data stream rates. The code assumes that
// streamRateRawSensors is the first // streamRateRawSensors is the first
AP_Int16 streamRateRawSensors; AP_Int16 streamRateRawSensors;
AP_Int16 streamRateExtendedStatus; AP_Int16 streamRateExtendedStatus;
AP_Int16 streamRateRCChannels; AP_Int16 streamRateRCChannels;
AP_Int16 streamRateRawController; AP_Int16 streamRateRawController;
AP_Int16 streamRatePosition; AP_Int16 streamRatePosition;
AP_Int16 streamRateExtra1; AP_Int16 streamRateExtra1;
AP_Int16 streamRateExtra2; AP_Int16 streamRateExtra2;
AP_Int16 streamRateExtra3; AP_Int16 streamRateExtra3;
AP_Int16 streamRateParams; AP_Int16 streamRateParams;
// number of 50Hz ticks until we next send this stream // number of 50Hz ticks until we next send this stream
uint8_t stream_ticks[NUM_STREAMS]; uint8_t stream_ticks[NUM_STREAMS];
// number of extra ticks to add to slow things down for the radio // number of extra ticks to add to slow things down for the radio
uint8_t stream_slowdown; uint8_t stream_slowdown;
}; };
#endif // __GCS_H #endif // __GCS_H

Loading…
Cancel
Save