APM:Libraries
GCS.h
Go to the documentation of this file.
1 // protocols.
4 #pragma once
5 
6 #include <AP_HAL/AP_HAL.h>
7 #include <AP_Common/AP_Common.h>
8 #include "GCS_MAVLink.h"
9 #include <DataFlash/DataFlash.h>
10 #include <AP_Mission/AP_Mission.h>
12 #include <stdint.h>
13 #include "MAVLink_routing.h"
15 #include <AP_Mount/AP_Mount.h>
21 #include <AP_Camera/AP_Camera.h>
24 #include <AP_Common/AP_FWVersion.h>
25 
26 // check if a message will fit in the payload space available
27 #define PAYLOAD_SIZE(chan, id) (GCS_MAVLINK::packet_overhead_chan(chan)+MAVLINK_MSG_ID_ ## id ## _LEN)
28 #define HAVE_PAYLOAD_SPACE(chan, id) (comm_get_txspace(chan) >= PAYLOAD_SIZE(chan, id))
29 #define CHECK_PAYLOAD_SIZE(id) if (comm_get_txspace(chan) < packet_overhead()+MAVLINK_MSG_ID_ ## id ## _LEN) return false
30 #define CHECK_PAYLOAD_SIZE2(id) if (!HAVE_PAYLOAD_SPACE(chan, id)) return false
31 
32 // GCS Message ID's
37 enum ap_message : uint8_t {
85  MSG_LAST // MSG_LAST must be the last entry in this enum
86 };
87 
88 // convenience macros for defining which ap_message ids are in which streams:
89 #define MAV_STREAM_ENTRY(stream_name) \
90  { \
91  GCS_MAVLINK::stream_name, \
92  stream_name ## _msgs, \
93  ARRAY_SIZE(stream_name ## _msgs) \
94  }
95 #define MAV_STREAM_TERMINATOR { (streams)0, nullptr, 0 }
96 
101 class GCS_MAVLINK
102 {
103 public:
104  friend class GCS;
105  GCS_MAVLINK();
106  void update(uint32_t max_time_us=1000);
107  void init(AP_HAL::UARTDriver *port, mavlink_channel_t mav_chan);
109  void send_message(enum ap_message id);
110  void send_text(MAV_SEVERITY severity, const char *fmt, ...);
111  void data_stream_send();
112  void queued_param_send();
113  void queued_waypoint_send();
114  // packetReceived is called on any successful decode of a mavlink message
115  virtual void packetReceived(const mavlink_status_t &status,
116  mavlink_message_t &msg);
117 
118  // accessor for uart
120 
121  virtual uint8_t sysid_my_gcs() const = 0;
122 
123  static const struct AP_Param::GroupInfo var_info[];
124 
125  // set to true if this GCS link is active
127 
128  // NOTE! The streams enum below and the
129  // set of AP_Int16 stream rates _must_ be
130  // kept in the same order
131  enum streams : uint8_t {
143  };
144 
145  // see if we should send a stream now. Called at 50Hz
146  bool stream_trigger(enum streams stream_num);
147 
148  bool is_high_bandwidth() { return chan == MAVLINK_COMM_0; }
149  // return true if this channel has hardware flow control
150  bool have_flow_control();
151 
152  mavlink_channel_t get_chan() const { return chan; }
153  uint32_t get_last_heartbeat_time() const { return last_heartbeat_time; };
154 
155  uint32_t last_heartbeat_time; // milliseconds
156 
157  // last time we got a non-zero RSSI from RADIO_STATUS
159 
160  // mission item index to be sent on queued msg, delayed or not
162 
163  // common send functions
164  void send_heartbeat(void) const;
165  void send_meminfo(void);
166  void send_power_status(void);
168  const uint8_t instance) const;
169  bool send_battery_status() const;
170  bool send_distance_sensor() const;
171  void send_rangefinder_downward() const;
172  bool send_proximity() const;
173  void send_ahrs2();
174  void send_system_time();
175  void send_radio_in();
176  void send_raw_imu();
177  virtual void send_scaled_pressure3(); // allow sub to override this
178  void send_scaled_pressure();
179  void send_sensor_offsets();
180  virtual void send_simstate() const;
181  void send_ahrs();
182  void send_battery2();
183 #if AP_AHRS_NAVEKF_AVAILABLE
184  void send_opticalflow(const OpticalFlow &optflow);
185 #endif
186  virtual void send_attitude() const;
187  void send_autopilot_version() const;
188  void send_local_position() const;
189  void send_vfr_hud();
190  void send_vibration() const;
191  void send_named_float(const char *name, float value) const;
192  void send_home() const;
193  void send_ekf_origin() const;
195  void send_servo_output_raw();
196  static void send_collision_all(const AP_Avoidance::Obstacle &threat, MAV_COLLISION_ACTION behaviour);
197  void send_accelcal_vehicle_position(uint32_t position);
198 
199  // return a bitmap of active channels. Used by libraries to loop
200  // over active channels to send to all active channels
201  static uint8_t active_channel_mask(void) { return mavlink_active; }
202 
203  // return a bitmap of streaming channels
204  static uint8_t streaming_channel_mask(void) { return chan_is_streaming; }
205 
206  // send queued parameters if needed
207  void send_queued_parameters(void);
208 
209  // push send_message() messages and queued statustext messages etc:
210  void retry_deferred();
211 
212  /*
213  send a MAVLink message to all components with this vehicle's system id
214  This is a no-op if no routes to components have been learned
215  */
216  static void send_to_components(const mavlink_message_t* msg) { routing.send_to_components(msg); }
217 
218  /*
219  allow forwarding of packets / heartbeats to be blocked as required by some components to reduce traffic
220  */
221  static void disable_channel_routing(mavlink_channel_t chan) { routing.no_route_mask |= (1U<<(chan-MAVLINK_COMM_0)); }
222 
223  /*
224  search for a component in the routing table with given mav_type and retrieve it's sysid, compid and channel
225  returns if a matching component is found
226  */
227  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); }
228 
229  // update signing timestamp on GPS lock
230  static void update_signing_timestamp(uint64_t timestamp_usec);
231 
232  // return current packet overhead for a channel
233  static uint8_t packet_overhead_chan(mavlink_channel_t chan);
234 
235  // alternative protocol function handler
236  FUNCTOR_TYPEDEF(protocol_handler_fn_t, bool, uint8_t, AP_HAL::UARTDriver *);
237 
238  struct stream_entries {
241  const uint8_t num_ap_message_ids;
242  };
243  // vehicle subclass cpp files should define this:
244  static const struct stream_entries all_stream_entries[];
245 
246 protected:
247 
248  virtual bool in_hil_mode() const { return false; }
249 
250  // overridable method to check for packet acceptance. Allows for
251  // enforcement of GCS sysid
252  virtual bool accept_packet(const mavlink_status_t &status, mavlink_message_t &msg) { return true; }
253  virtual AP_Mission *get_mission() = 0;
254  virtual AP_Rally *get_rally() const = 0;
255  virtual Compass *get_compass() const = 0;
256  virtual class AP_Camera *get_camera() const = 0;
257  virtual AP_AdvancedFailsafe *get_advanced_failsafe() const { return nullptr; };
258  virtual AP_VisualOdom *get_visual_odom() const { return nullptr; }
259  virtual bool set_mode(uint8_t mode) = 0;
260  virtual const AP_FWVersion &get_fwver() const = 0;
261  void set_ekf_origin(const Location& loc);
262 
263  virtual MAV_TYPE frame_type() const = 0;
264  virtual MAV_MODE base_mode() const = 0;
265  virtual uint32_t custom_mode() const = 0;
266  virtual MAV_STATE system_status() const = 0;
267 
268  bool waypoint_receiving; // currently receiving
269  // the following two variables are only here because of Tracker
270  uint16_t waypoint_request_i; // request index
271  uint16_t waypoint_request_last; // last request index
272 
274  // be sent in queue
275  mavlink_channel_t chan;
276  uint8_t packet_overhead(void) const { return packet_overhead_chan(chan); }
277 
278  // saveable rate of each stream
280 
281  virtual bool persist_streamrates() const { return false; }
282  void handle_request_data_stream(mavlink_message_t *msg);
283 
284  virtual void handle_command_ack(const mavlink_message_t* msg);
285  void handle_set_mode(mavlink_message_t* msg);
286  void handle_mission_request_list(AP_Mission &mission, mavlink_message_t *msg);
287  void handle_mission_request(AP_Mission &mission, mavlink_message_t *msg);
288  void handle_mission_clear_all(AP_Mission &mission, mavlink_message_t *msg);
289  virtual void handle_mission_set_current(AP_Mission &mission, mavlink_message_t *msg);
290  void handle_mission_count(AP_Mission &mission, mavlink_message_t *msg);
291  void handle_mission_write_partial_list(AP_Mission &mission, mavlink_message_t *msg);
292  bool handle_mission_item(mavlink_message_t *msg, AP_Mission &mission);
293 
294  void handle_common_param_message(mavlink_message_t *msg);
295  void handle_param_set(mavlink_message_t *msg);
296  void handle_param_request_list(mavlink_message_t *msg);
297  void handle_param_request_read(mavlink_message_t *msg);
298  virtual bool params_ready() const { return true; }
299 
300  void handle_common_gps_message(mavlink_message_t *msg);
301  void handle_common_rally_message(mavlink_message_t *msg);
302  void handle_rally_fetch_point(mavlink_message_t *msg);
303  void handle_rally_point(mavlink_message_t *msg);
304  void handle_common_camera_message(const mavlink_message_t *msg);
305  void handle_gimbal_report(AP_Mount &mount, mavlink_message_t *msg) const;
306  void handle_radio_status(mavlink_message_t *msg, DataFlash_Class &dataflash, bool log_radio);
307  void handle_serial_control(const mavlink_message_t *msg);
308  void handle_vision_position_delta(mavlink_message_t *msg);
309 
310  void handle_common_message(mavlink_message_t *msg);
311  void handle_set_gps_global_origin(const mavlink_message_t *msg);
312  void handle_setup_signing(const mavlink_message_t *msg);
313  MAV_RESULT handle_preflight_reboot(const mavlink_command_long_t &packet, bool disable_overrides);
314  MAV_RESULT handle_rc_bind(const mavlink_command_long_t &packet);
315  virtual MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet);
316 
317  void handle_send_autopilot_version(const mavlink_message_t *msg);
318  MAV_RESULT handle_command_request_autopilot_capabilities(const mavlink_command_long_t &packet);
319 
320  virtual void send_banner();
321 
322  void handle_device_op_read(mavlink_message_t *msg);
323  void handle_device_op_write(mavlink_message_t *msg);
324 
325  void send_timesync();
326  // returns the time a timesync message was most likely received:
327  uint64_t timesync_receive_timestamp_ns() const;
328  // returns a timestamp suitable for packing into the ts1 field of TIMESYNC:
329  uint64_t timesync_timestamp_ns() const;
330  void handle_timesync(mavlink_message_t *msg);
331  struct {
332  int64_t sent_ts1;
333  uint32_t last_sent_ms;
334  const uint16_t interval_ms = 10000;
336 
337  void handle_statustext(mavlink_message_t *msg);
338 
339  bool telemetry_delayed() const;
340  virtual uint32_t telem_delay() const = 0;
341 
342  MAV_RESULT handle_command_preflight_set_sensor_offsets(const mavlink_command_long_t &packet);
343 
344  // generally this should not be overridden; Plane overrides it to ensure
345  // failsafe isn't triggered during calibation
346  virtual MAV_RESULT handle_command_preflight_calibration(const mavlink_command_long_t &packet);
347 
348  virtual MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_long_t &packet);
349  virtual MAV_RESULT _handle_command_preflight_calibration_baro();
350 
351  MAV_RESULT handle_command_mag_cal(const mavlink_command_long_t &packet);
352  MAV_RESULT handle_command_long_message(mavlink_command_long_t &packet);
353  MAV_RESULT handle_command_camera(const mavlink_command_long_t &packet);
354  MAV_RESULT handle_command_do_send_banner(const mavlink_command_long_t &packet);
355  MAV_RESULT handle_command_do_set_mode(const mavlink_command_long_t &packet);
356  MAV_RESULT handle_command_get_home_position(const mavlink_command_long_t &packet);
357 
358  // vehicle-overridable message send function
359  virtual bool try_send_message(enum ap_message id);
360 
361  // message sending functions:
362  bool try_send_compass_message(enum ap_message id);
363  bool try_send_mission_message(enum ap_message id);
364  bool try_send_camera_message(enum ap_message id);
365  bool try_send_gps_message(enum ap_message id);
366  void send_hwstatus();
367  void handle_data_packet(mavlink_message_t *msg);
368 
369  // these two methods are called after current_loc is updated:
370  virtual int32_t global_position_int_alt() const;
371  virtual int32_t global_position_int_relative_alt() const;
372 
373  // these methods are called after vfr_hud_velned is updated
374  virtual bool vfr_hud_make_alt_relative() const { return false; }
375  virtual float vfr_hud_climbrate() const;
376  virtual float vfr_hud_airspeed() const;
377  virtual int16_t vfr_hud_throttle() const { return 0; }
379 
380 private:
381 
382  float adjust_rate_for_stream_trigger(enum streams stream_num);
383 
384  MAV_RESULT _set_mode_common(const MAV_MODE base_mode, const uint32_t custom_mode);
385 
386  virtual void handleMessage(mavlink_message_t * msg) = 0;
387 
388  MAV_RESULT handle_servorelay_message(mavlink_command_long_t &packet);
389 
390  bool calibrate_gyros();
391 
394 
398  // parameter
400  // next() call
402  // parameter's index
404  // parameters for
405  // queued send
407 
411  // that are
413  // expect when it
418  uint16_t packet_drops;
419 
420  // waypoints
421  uint16_t waypoint_dest_sysid; // where to send requests
422  uint16_t waypoint_dest_compid; // "
423  uint16_t waypoint_count;
424  uint32_t waypoint_timelast_receive; // milliseconds
425  uint32_t waypoint_timelast_request; // milliseconds
426  const uint16_t waypoint_receive_timeout = 8000; // milliseconds
427 
428  // number of 50Hz ticks until we next send this stream
430 
431  // number of extra ticks to add to slow things down for the radio
433 
434  // perf counters
439 
440  // deferred message handling. We size the deferred_message
441  // ringbuffer so we can defer every message type
445 
446  // time when we missed sending a parameter for GCS
448 
449  // bitmask of what mavlink channels are active
450  static uint8_t mavlink_active;
451 
452  // bitmask of what mavlink channels are streaming
453  static uint8_t chan_is_streaming;
454 
455  // mavlink routing object
457 
458  // pointer to static frsky_telem for queueing of text messages
460 
462 
464  mavlink_channel_t chan;
465  int16_t param_index;
466  char param_name[AP_MAX_NAME_SIZE+1];
467  };
468 
470  mavlink_channel_t chan;
471  float value;
472  enum ap_var_type p_type;
473  int16_t param_index;
474  uint16_t count;
475  char param_name[AP_MAX_NAME_SIZE+1];
476  };
477 
478  // queue of pending parameter requests and replies
481 
482  // have we registered the IO timer callback?
484 
485  // IO timer callback for parameters
486  void param_io_timer(void);
487 
488  // send an async parameter reply
489  void send_parameter_reply(void);
490 
491  void send_distance_sensor(const AP_RangeFinder_Backend *sensor, const uint8_t instance) const;
492 
493  virtual bool handle_guided_request(AP_Mission::Mission_Command &cmd) = 0;
495  void handle_common_mission_message(mavlink_message_t *msg);
496 
497  void handle_vicon_position_estimate(mavlink_message_t *msg);
498  void handle_vision_position_estimate(mavlink_message_t *msg);
499  void handle_global_vision_position_estimate(mavlink_message_t *msg);
500  void handle_att_pos_mocap(mavlink_message_t *msg);
501  void handle_common_vision_position_estimate_data(const uint64_t usec,
502  const float x,
503  const float y,
504  const float z,
505  const float roll,
506  const float pitch,
507  const float yaw,
508  const uint16_t payload_size);
509  void log_vision_position_estimate_data(const uint64_t usec,
510  const float x,
511  const float y,
512  const float z,
513  const float roll,
514  const float pitch,
515  const float yaw);
516  void push_deferred_messages();
517 
518  void lock_channel(mavlink_channel_t chan, bool lock);
519 
520  /*
521  correct an offboard timestamp in microseconds to a local time
522  since boot in milliseconds
523  */
524  uint32_t correct_offboard_timestamp_usec_to_ms(uint64_t offboard_usec, uint16_t payload_size);
525 
526  mavlink_signing_t signing;
527  static mavlink_signing_streams_t signing_streams;
528  static uint32_t last_signing_save_ms;
529 
531  static bool signing_key_save(const struct SigningKey &key);
532  static bool signing_key_load(struct SigningKey &key);
533  void load_signing_key(void);
534  bool signing_enabled(void) const;
535  static void save_signing_timestamp(bool force_save_now);
536 
537  // alternative protocol handler support
538  struct {
539  GCS_MAVLINK::protocol_handler_fn_t handler;
540  uint32_t last_mavlink_ms;
542  bool active;
543  } alternative;
544 
545  // state associated with offboard transport lag correction
546  struct {
547  bool initialised;
550  int64_t min_sample_us;
551  } lag_correction;
552 
553  // we cache the current location and send it even if the AHRS has
554  // no idea where we are:
556 
558 };
559 
562 class GCS
563 {
564 
565 public:
566 
567  GCS() {
568  if (_singleton == nullptr) {
569  _singleton = this;
570  } else {
571 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
572  // this is a serious problem, but we don't need to kill a
573  // real vehicle
574  AP_HAL::panic("GCS must be singleton");
575 #endif
576  }
577  };
578 
579  static class GCS *instance() {
580  return _singleton;
581  }
582 
583  void send_text(MAV_SEVERITY severity, const char *fmt, ...);
584  virtual void send_statustext(MAV_SEVERITY severity, uint8_t dest_bitmask, const char *text);
585  void service_statustext(void);
586  virtual GCS_MAVLINK &chan(const uint8_t ofs) = 0;
587  virtual const GCS_MAVLINK &chan(const uint8_t ofs) const = 0;
588  virtual uint8_t num_gcs() const = 0;
589  void send_message(enum ap_message id);
590  void send_mission_item_reached_message(uint16_t mission_index);
591  void send_named_float(const char *name, float value) const;
592  void send_home() const;
593  void send_ekf_origin() const;
594 
595  void send_parameter_value(const char *param_name,
596  ap_var_type param_type,
597  float param_value);
598 
599  // push send_message() messages and queued statustext messages etc:
600  void retry_deferred();
601  void data_stream_send();
602  void update();
604 
605  bool out_of_time() const {
606  return _out_of_time;
607  }
608  void set_out_of_time(bool val) {
609  _out_of_time = val;
610  }
611 
612  /*
613  set a dataflash pointer for logging
614  */
615  void set_dataflash(DataFlash_Class *dataflash) {
616  dataflash_p = dataflash;
617  }
618 
619  // pointer to static dataflash for logging of text messages
621 
622 
623  /*
624  set a frsky_telem pointer for queueing
625  */
627  frsky_telemetry_p = frsky_telemetry;
628  }
629 
630  // static frsky_telem pointer to support queueing text messages
632 
633 
634  // install an alternative protocol handler
635  bool install_alternative_protocol(mavlink_channel_t chan, GCS_MAVLINK::protocol_handler_fn_t handler);
636 
637 private:
638 
639  static GCS *_singleton;
640 
641  struct statustext_t {
642  uint8_t bitmask;
643  mavlink_statustext_t msg;
644  };
645 
646 #if HAL_CPU_CLASS <= HAL_CPU_CLASS_150 || CONFIG_HAL_BOARD == HAL_BOARD_SITL
647  static const uint8_t _status_capacity = 5;
648 #else
649  static const uint8_t _status_capacity = 30;
650 #endif
651 
652  ObjectArray<statustext_t> _statustext_queue{_status_capacity};
653 
654  // true if we are running short on time in our main loop
656 };
657 
658 GCS &gcs();
void set_dataflash(DataFlash_Class *dataflash)
Definition: GCS.h:615
static AP_SerialManager serial_manager
Definition: AHRS_Test.cpp:24
Object managing Rally Points.
Definition: AP_Rally.h:37
Definition: GCS.h:60
virtual void setup_uarts(AP_SerialManager &serial_manager)
void send_mission_item_reached_message(uint16_t mission_index)
ap_var_type
Definition: AP_Param.h:124
#define AP_MAX_NAME_SIZE
Definition: AP_Param.h:32
GCS()
Definition: GCS.h:567
void send_parameter_value(const char *param_name, ap_var_type param_type, float param_value)
Definition: GCS_Param.cpp:325
Object managing Mission.
Definition: AP_Mission.h:45
mavlink_statustext_t msg
Definition: GCS.h:643
Definition: GCS.h:77
ap_message
Definition: GCS.h:37
Definition: GCS.h:63
Definition: GCS.h:85
void service_statustext(void)
GCS & gcs()
global GCS object
Definition: GCS.h:562
DataFlash_Class * dataflash_p
Definition: GCS.h:620
const char * name
Definition: BusTest.cpp:11
void register_frsky_telemetry_callback(AP_Frsky_Telem *frsky_telemetry)
Definition: GCS.h:626
static GCS * _singleton
Definition: GCS.h:639
bool _out_of_time
Definition: GCS.h:655
#define x(i)
void * perf_counter_t
Definition: Util.h:101
virtual void send_statustext(MAV_SEVERITY severity, uint8_t dest_bitmask, const char *text)
const char * fmt
Definition: Printf.cpp:14
static OpticalFlow optflow
uint8_t bitmask
Definition: GCS.h:642
Handles the MAVLINK command mission stack. Reads and writes mission to storage.
void set_out_of_time(bool val)
Definition: GCS.h:608
AP_BattMonitor & battery()
Common definitions and utility routines for the ArduPilot libraries.
static const uint8_t num_gcs
Definition: routing.cpp:56
#define AP_MISSION_CMD_INDEX_NONE
Definition: AP_Mission.h:33
AP_Frsky_Telem * frsky_telemetry_p
Definition: GCS.h:631
static class GCS * instance()
Definition: GCS.h:579
bool out_of_time() const
Definition: GCS.h:605
float value
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
bool install_alternative_protocol(mavlink_channel_t chan, GCS_MAVLINK::protocol_handler_fn_t handler)
Definition: GCS.cpp:52
Photo or video camera manager, with EEPROM-backed storage of constants.