GCS.h 34 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848
  1. /// @file GCS.h
  2. /// @brief Interface definition for the various Ground Control System
  3. // protocols.
  4. #pragma once
  5. #include <AP_HAL/AP_HAL.h>
  6. #include <AP_Common/AP_Common.h>
  7. #include "GCS_MAVLink.h"
  8. #include <AP_Mission/AP_Mission.h>
  9. #include <stdint.h>
  10. #include "MAVLink_routing.h"
  11. #include <AP_Frsky_Telem/AP_Frsky_Telem.h>
  12. #include <AP_AdvancedFailsafe/AP_AdvancedFailsafe.h>
  13. #include <AP_RTC/JitterCorrection.h>
  14. #include <AP_Common/Bitmask.h>
  15. #include <AP_Devo_Telem/AP_Devo_Telem.h>
  16. #include <RC_Channel/RC_Channel.h>
  17. #include "MissionItemProtocol_Waypoints.h"
  18. #include "MissionItemProtocol_Rally.h"
  19. #include "ap_message.h"
  20. #define GCS_DEBUG_SEND_MESSAGE_TIMINGS 0
  21. // check if a message will fit in the payload space available
  22. #define PAYLOAD_SIZE(chan, id) (GCS_MAVLINK::packet_overhead_chan(chan)+MAVLINK_MSG_ID_ ## id ## _LEN)
  23. #define HAVE_PAYLOAD_SPACE(chan, id) (comm_get_txspace(chan) >= PAYLOAD_SIZE(chan, id))
  24. #define CHECK_PAYLOAD_SIZE(id) if (comm_get_txspace(chan) < packet_overhead()+MAVLINK_MSG_ID_ ## id ## _LEN) return false
  25. #define CHECK_PAYLOAD_SIZE2(id) if (!HAVE_PAYLOAD_SPACE(chan, id)) return false
  26. // convenience macros for defining which ap_message ids are in which streams:
  27. #define MAV_STREAM_ENTRY(stream_name) \
  28. { \
  29. GCS_MAVLINK::stream_name, \
  30. stream_name ## _msgs, \
  31. ARRAY_SIZE(stream_name ## _msgs) \
  32. }
  33. #define MAV_STREAM_TERMINATOR { (streams)0, nullptr, 0 }
  34. #define GCS_MAVLINK_NUM_STREAM_RATES 10
  35. class GCS_MAVLINK_Parameters
  36. {
  37. public:
  38. GCS_MAVLINK_Parameters();
  39. static const struct AP_Param::GroupInfo var_info[];
  40. // saveable rate of each stream
  41. AP_Int16 streamRates[GCS_MAVLINK_NUM_STREAM_RATES];
  42. };
  43. ///
  44. /// @class GCS_MAVLINK
  45. /// @brief MAVLink transport control class
  46. ///
  47. class GCS_MAVLINK
  48. {
  49. public:
  50. friend class GCS;
  51. GCS_MAVLINK(GCS_MAVLINK_Parameters &parameters, AP_HAL::UARTDriver &uart);
  52. virtual ~GCS_MAVLINK() {}
  53. void update_receive(uint32_t max_time_us=1000);
  54. void update_send();
  55. bool init(uint8_t instance);
  56. void send_message(enum ap_message id);
  57. void send_text(MAV_SEVERITY severity, const char *fmt, ...) const FMT_PRINTF(3, 4);
  58. void queued_param_send();
  59. void queued_mission_request_send();
  60. bool sending_mavlink1() const;
  61. // returns true if we are requesting any items from the GCS:
  62. bool requesting_mission_items() const;
  63. void send_mission_ack(const mavlink_message_t &msg,
  64. MAV_MISSION_TYPE mission_type,
  65. MAV_MISSION_RESULT result) const {
  66. mavlink_msg_mission_ack_send(chan,
  67. msg.sysid,
  68. msg.compid,
  69. result,
  70. mission_type);
  71. }
  72. static const MAV_MISSION_TYPE supported_mission_types[2];
  73. // packetReceived is called on any successful decode of a mavlink message
  74. virtual void packetReceived(const mavlink_status_t &status,
  75. const mavlink_message_t &msg);
  76. // send a mavlink_message_t out this GCS_MAVLINK connection.
  77. // Caller is responsible for ensuring space.
  78. void send_message(uint32_t msgid, const char *pkt) const {
  79. const mavlink_msg_entry_t *entry = mavlink_get_msg_entry(msgid);
  80. if (entry == nullptr) {
  81. return;
  82. }
  83. send_message(pkt, entry);
  84. }
  85. void send_message(const char *pkt, const mavlink_msg_entry_t *entry) const {
  86. _mav_finalize_message_chan_send(chan,
  87. entry->msgid,
  88. pkt,
  89. entry->min_msg_len,
  90. entry->max_msg_len,
  91. entry->crc_extra);
  92. }
  93. // accessor for uart
  94. AP_HAL::UARTDriver *get_uart() { return _port; }
  95. virtual uint8_t sysid_my_gcs() const = 0;
  96. virtual bool sysid_enforce() const { return false; }
  97. void send_parameter_value(const char *param_name,
  98. ap_var_type param_type,
  99. float param_value);
  100. // NOTE! The streams enum below and the
  101. // set of AP_Int16 stream rates _must_ be
  102. // kept in the same order
  103. enum streams : uint8_t {
  104. STREAM_RAW_SENSORS,
  105. STREAM_EXTENDED_STATUS,
  106. STREAM_RC_CHANNELS,
  107. STREAM_RAW_CONTROLLER,
  108. STREAM_POSITION,
  109. STREAM_EXTRA1,
  110. STREAM_EXTRA2,
  111. STREAM_EXTRA3,
  112. STREAM_PARAMS,
  113. STREAM_ADSB,
  114. NUM_STREAMS
  115. };
  116. // streams must be moved out into the top level for
  117. // GCS_MAVLINK_Parameters to be able to use it. This is an
  118. // extensive change, so we 'll just keep them in sync with a
  119. // static assert for now:
  120. static_assert(NUM_STREAMS == GCS_MAVLINK_NUM_STREAM_RATES, "num streams must equal num stream rates");
  121. bool is_high_bandwidth() { return chan == MAVLINK_COMM_0; }
  122. // return true if this channel has hardware flow control
  123. bool have_flow_control();
  124. bool is_active() const {
  125. return GCS_MAVLINK::active_channel_mask() & (1 << (chan-MAVLINK_COMM_0));
  126. }
  127. bool is_streaming() const {
  128. return sending_bucket_id != no_bucket_to_send;
  129. }
  130. mavlink_channel_t get_chan() const { return chan; }
  131. uint32_t get_last_heartbeat_time() const { return last_heartbeat_time; };
  132. uint32_t last_heartbeat_time; // milliseconds
  133. // last time we got a non-zero RSSI from RADIO_STATUS
  134. static uint32_t last_radio_status_remrssi_ms;
  135. // mission item index to be sent on queued msg, delayed or not
  136. uint16_t mission_item_reached_index = AP_MISSION_CMD_INDEX_NONE;
  137. // common send functions
  138. void send_heartbeat(void) const;
  139. void send_meminfo(void);
  140. void send_fence_status() const;
  141. void send_power_status(void);
  142. void send_battery_status(const uint8_t instance) const;
  143. bool send_battery_status() const;
  144. void send_distance_sensor() const;
  145. // send_rangefinder sends only if a downward-facing instance is
  146. // found. Rover overrides this!
  147. virtual void send_rangefinder() const;
  148. void send_proximity() const;
  149. virtual void send_nav_controller_output() const = 0;
  150. virtual void send_pid_tuning() = 0;
  151. void send_ahrs2();
  152. void send_ahrs3();
  153. void send_system_time();
  154. void send_rc_channels() const;
  155. void send_rc_channels_raw() const;
  156. void send_raw_imu();
  157. void send_scaled_pressure_instance(uint8_t instance, void (*send_fn)(mavlink_channel_t chan, uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature));
  158. void send_scaled_pressure();
  159. void send_scaled_pressure2();
  160. virtual void send_scaled_pressure3(); // allow sub to override this
  161. void send_sensor_offsets();
  162. virtual void send_simstate() const;
  163. void send_ahrs();
  164. void send_battery2();
  165. void send_opticalflow();
  166. virtual void send_attitude() const;
  167. void send_autopilot_version() const;
  168. void send_extended_sys_state() const;
  169. void send_local_position() const;
  170. void send_vfr_hud();
  171. void send_vibration() const;
  172. void send_mount_status() const;
  173. void send_named_float(const char *name, float value) const;
  174. void send_gimbal_report() const;
  175. void send_home_position() const;
  176. void send_gps_global_origin() const;
  177. virtual void send_position_target_global_int() { };
  178. virtual void send_position_target_local_ned() { };
  179. void send_servo_output_raw();
  180. void send_accelcal_vehicle_position(uint32_t position);
  181. void send_scaled_imu(uint8_t instance, void (*send_fn)(mavlink_channel_t chan, uint32_t time_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag));
  182. void send_sys_status();
  183. void send_set_position_target_global_int(uint8_t target_system, uint8_t target_component, const Location& loc);
  184. void send_rpm() const;
  185. bool locked() const;
  186. // return a bitmap of active channels. Used by libraries to loop
  187. // over active channels to send to all active channels
  188. static uint8_t active_channel_mask(void) { return mavlink_active; }
  189. // return a bitmap of streaming channels
  190. static uint8_t streaming_channel_mask(void) { return chan_is_streaming; }
  191. // set a channel as private. Private channels get sent heartbeats, but
  192. // don't get broadcast packets or forwarded packets
  193. static void set_channel_private(mavlink_channel_t chan);
  194. // return true if channel is private
  195. static bool is_private(mavlink_channel_t _chan) {
  196. return (mavlink_private & (1U<<(unsigned)_chan)) != 0;
  197. }
  198. // return true if channel is private
  199. bool is_private(void) const { return is_private(chan); }
  200. /*
  201. send a MAVLink message to all components with this vehicle's system id
  202. This is a no-op if no routes to components have been learned
  203. */
  204. static void send_to_components(const mavlink_message_t &msg) { routing.send_to_components(msg); }
  205. /*
  206. allow forwarding of packets / heartbeats to be blocked as required by some components to reduce traffic
  207. */
  208. static void disable_channel_routing(mavlink_channel_t chan) { routing.no_route_mask |= (1U<<(chan-MAVLINK_COMM_0)); }
  209. /*
  210. search for a component in the routing table with given mav_type and retrieve it's sysid, compid and channel
  211. returns if a matching component is found
  212. */
  213. 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); }
  214. // update signing timestamp on GPS lock
  215. static void update_signing_timestamp(uint64_t timestamp_usec);
  216. // return current packet overhead for a channel
  217. static uint8_t packet_overhead_chan(mavlink_channel_t chan);
  218. // alternative protocol function handler
  219. FUNCTOR_TYPEDEF(protocol_handler_fn_t, bool, uint8_t, AP_HAL::UARTDriver *);
  220. struct stream_entries {
  221. const streams stream_id;
  222. const ap_message *ap_message_ids;
  223. const uint8_t num_ap_message_ids;
  224. };
  225. // vehicle subclass cpp files should define this:
  226. static const struct stream_entries all_stream_entries[];
  227. virtual uint64_t capabilities() const;
  228. uint8_t get_stream_slowdown_ms() const { return stream_slowdown_ms; }
  229. protected:
  230. virtual bool in_hil_mode() const { return false; }
  231. bool mavlink_coordinate_frame_to_location_alt_frame(MAV_FRAME coordinate_frame,
  232. Location::AltFrame &frame);
  233. // overridable method to check for packet acceptance. Allows for
  234. // enforcement of GCS sysid
  235. bool accept_packet(const mavlink_status_t &status, const mavlink_message_t &msg);
  236. virtual AP_AdvancedFailsafe *get_advanced_failsafe() const { return nullptr; };
  237. virtual bool set_mode(uint8_t mode) = 0;
  238. void set_ekf_origin(const Location& loc);
  239. virtual MAV_MODE base_mode() const = 0;
  240. virtual MAV_STATE system_status() const = 0;
  241. virtual MAV_VTOL_STATE vtol_state() const { return MAV_VTOL_STATE_UNDEFINED; }
  242. virtual MAV_LANDED_STATE landed_state() const { return MAV_LANDED_STATE_UNDEFINED; }
  243. // return a MAVLink parameter type given a AP_Param type
  244. static MAV_PARAM_TYPE mav_param_type(enum ap_var_type t);
  245. AP_Param * _queued_parameter; ///< next parameter to
  246. // be sent in queue
  247. mavlink_channel_t chan;
  248. uint8_t packet_overhead(void) const { return packet_overhead_chan(chan); }
  249. // saveable rate of each stream
  250. AP_Int16 *streamRates;
  251. virtual bool persist_streamrates() const { return false; }
  252. void handle_request_data_stream(const mavlink_message_t &msg);
  253. virtual void handle_command_ack(const mavlink_message_t &msg);
  254. void handle_set_mode(const mavlink_message_t &msg);
  255. void handle_command_int(const mavlink_message_t &msg);
  256. MAV_RESULT handle_command_int_do_set_home(const mavlink_command_int_t &packet);
  257. virtual MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet);
  258. virtual bool set_home_to_current_location(bool lock) = 0;
  259. virtual bool set_home(const Location& loc, bool lock) = 0;
  260. MAV_RESULT handle_command_do_set_home(const mavlink_command_long_t &packet);
  261. void handle_mission_request_list(const mavlink_message_t &msg);
  262. void handle_mission_request(const mavlink_message_t &msg);
  263. void handle_mission_request_int(const mavlink_message_t &msg);
  264. void handle_mission_clear_all(const mavlink_message_t &msg);
  265. virtual void handle_mission_set_current(AP_Mission &mission, const mavlink_message_t &msg);
  266. void handle_mission_count(const mavlink_message_t &msg);
  267. void handle_mission_write_partial_list(const mavlink_message_t &msg);
  268. void handle_mission_item(const mavlink_message_t &msg);
  269. void handle_common_param_message(const mavlink_message_t &msg);
  270. void handle_param_set(const mavlink_message_t &msg);
  271. void handle_param_request_list(const mavlink_message_t &msg);
  272. void handle_param_request_read(const mavlink_message_t &msg);
  273. virtual bool params_ready() const { return true; }
  274. virtual void handle_rc_channels_override(const mavlink_message_t &msg);
  275. void handle_system_time_message(const mavlink_message_t &msg);
  276. void handle_common_rally_message(const mavlink_message_t &msg);
  277. void handle_rally_fetch_point(const mavlink_message_t &msg);
  278. void handle_rally_point(const mavlink_message_t &msg);
  279. virtual void handle_mount_message(const mavlink_message_t &msg);
  280. void handle_fence_message(const mavlink_message_t &msg);
  281. void handle_param_value(const mavlink_message_t &msg);
  282. void handle_radio_status(const mavlink_message_t &msg, bool log_radio);
  283. void handle_serial_control(const mavlink_message_t &msg);
  284. void handle_vision_position_delta(const mavlink_message_t &msg);
  285. void handle_common_message(const mavlink_message_t &msg);
  286. void handle_set_gps_global_origin(const mavlink_message_t &msg);
  287. void handle_setup_signing(const mavlink_message_t &msg);
  288. virtual bool should_zero_rc_outputs_on_reboot() const { return false; }
  289. MAV_RESULT handle_preflight_reboot(const mavlink_command_long_t &packet);
  290. // reset a message interval via mavlink:
  291. MAV_RESULT handle_command_set_message_interval(const mavlink_command_long_t &packet);
  292. MAV_RESULT handle_command_get_message_interval(const mavlink_command_long_t &packet);
  293. bool get_ap_message_interval(ap_message id, uint16_t &interval_ms) const;
  294. MAV_RESULT handle_command_request_message(const mavlink_command_long_t &packet);
  295. MAV_RESULT handle_rc_bind(const mavlink_command_long_t &packet);
  296. virtual MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet);
  297. void handle_send_autopilot_version(const mavlink_message_t &msg);
  298. MAV_RESULT handle_command_request_autopilot_capabilities(const mavlink_command_long_t &packet);
  299. virtual void send_banner();
  300. void handle_device_op_read(const mavlink_message_t &msg);
  301. void handle_device_op_write(const mavlink_message_t &msg);
  302. void send_timesync();
  303. // returns the time a timesync message was most likely received:
  304. uint64_t timesync_receive_timestamp_ns() const;
  305. // returns a timestamp suitable for packing into the ts1 field of TIMESYNC:
  306. uint64_t timesync_timestamp_ns() const;
  307. void handle_timesync(const mavlink_message_t &msg);
  308. struct {
  309. int64_t sent_ts1;
  310. uint32_t last_sent_ms;
  311. const uint16_t interval_ms = 10000;
  312. } _timesync_request;
  313. void handle_statustext(const mavlink_message_t &msg);
  314. bool telemetry_delayed() const;
  315. virtual uint32_t telem_delay() const = 0;
  316. MAV_RESULT handle_command_preflight_set_sensor_offsets(const mavlink_command_long_t &packet);
  317. MAV_RESULT handle_command_flash_bootloader(const mavlink_command_long_t &packet);
  318. // generally this should not be overridden; Plane overrides it to ensure
  319. // failsafe isn't triggered during calibration
  320. virtual MAV_RESULT handle_command_preflight_calibration(const mavlink_command_long_t &packet);
  321. virtual MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_long_t &packet);
  322. virtual MAV_RESULT _handle_command_preflight_calibration_baro();
  323. MAV_RESULT handle_command_preflight_can(const mavlink_command_long_t &packet);
  324. MAV_RESULT handle_command_battery_reset(const mavlink_command_long_t &packet);
  325. void handle_command_long(const mavlink_message_t &msg);
  326. MAV_RESULT handle_command_accelcal_vehicle_pos(const mavlink_command_long_t &packet);
  327. virtual MAV_RESULT handle_command_mount(const mavlink_command_long_t &packet);
  328. MAV_RESULT handle_command_mag_cal(const mavlink_command_long_t &packet);
  329. virtual MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet);
  330. MAV_RESULT handle_command_camera(const mavlink_command_long_t &packet);
  331. MAV_RESULT handle_command_do_send_banner(const mavlink_command_long_t &packet);
  332. MAV_RESULT handle_command_do_set_roi(const mavlink_command_int_t &packet);
  333. MAV_RESULT handle_command_do_set_roi(const mavlink_command_long_t &packet);
  334. virtual MAV_RESULT handle_command_do_set_roi(const Location &roi_loc);
  335. MAV_RESULT handle_command_do_gripper(const mavlink_command_long_t &packet);
  336. MAV_RESULT handle_command_do_set_mode(const mavlink_command_long_t &packet);
  337. MAV_RESULT handle_command_get_home_position(const mavlink_command_long_t &packet);
  338. MAV_RESULT handle_command_do_fence_enable(const mavlink_command_long_t &packet);
  339. void handle_optical_flow(const mavlink_message_t &msg);
  340. // vehicle-overridable message send function
  341. virtual bool try_send_message(enum ap_message id);
  342. virtual void send_global_position_int();
  343. // message sending functions:
  344. bool try_send_mission_message(enum ap_message id);
  345. void send_hwstatus();
  346. void handle_data_packet(const mavlink_message_t &msg);
  347. // these two methods are called after current_loc is updated:
  348. virtual int32_t global_position_int_alt() const;
  349. virtual int32_t global_position_int_relative_alt() const;
  350. virtual float vfr_hud_climbrate() const;
  351. virtual float vfr_hud_airspeed() const;
  352. virtual int16_t vfr_hud_throttle() const { return 0; }
  353. virtual float vfr_hud_alt() const;
  354. virtual uint8_t get_battery_remaining_percentage(uint8_t instance=0) const;
  355. static constexpr const float magic_force_arm_value = 2989.0f;
  356. static constexpr const float magic_force_disarm_value = 21196.0f;
  357. virtual bool allow_disarm() const { return true; }
  358. void manual_override(RC_Channel *c, int16_t value_in, uint16_t offset, float scaler, const uint32_t tnow, bool reversed = false);
  359. private:
  360. void log_mavlink_stats();
  361. MAV_RESULT _set_mode_common(const MAV_MODE base_mode, const uint32_t custom_mode);
  362. virtual void handleMessage(const mavlink_message_t &msg) = 0;
  363. MAV_RESULT handle_servorelay_message(const mavlink_command_long_t &packet);
  364. static bool command_long_stores_location(const MAV_CMD command);
  365. static void convert_COMMAND_LONG_to_COMMAND_INT(const mavlink_command_long_t &in, mavlink_command_int_t &out);
  366. bool calibrate_gyros();
  367. /// The stream we are communicating over
  368. AP_HAL::UARTDriver *_port;
  369. /// Perform queued sending operations
  370. ///
  371. enum ap_var_type _queued_parameter_type; ///< type of the next
  372. // parameter
  373. AP_Param::ParamToken _queued_parameter_token; ///AP_Param token for
  374. // next() call
  375. uint16_t _queued_parameter_index; ///< next queued
  376. // parameter's index
  377. uint16_t _queued_parameter_count; ///< saved count of
  378. // parameters for
  379. // queued send
  380. uint32_t _queued_parameter_send_time_ms;
  381. /// Count the number of reportable parameters.
  382. ///
  383. /// Not all parameters can be reported via MAVlink. We count the number
  384. // that are
  385. /// so that we can report to a GCS the number of parameters it should
  386. // expect when it
  387. /// requests the full set.
  388. ///
  389. /// @return The number of reportable parameters.
  390. ///
  391. uint16_t packet_drops;
  392. // number of extra ms to add to slow things down for the radio
  393. uint16_t stream_slowdown_ms;
  394. // perf counters
  395. AP_HAL::Util::perf_counter_t _perf_packet;
  396. AP_HAL::Util::perf_counter_t _perf_update;
  397. char _perf_packet_name[16];
  398. char _perf_update_name[16];
  399. // outbound ("deferred message") queue.
  400. // "special" messages such as heartbeat, next_param etc are stored
  401. // separately to stream-rated messages like AHRS2 etc. If these
  402. // were to be stored in buckets then they would be slowed down
  403. // based on stream_slowdown, which we have not traditionally done.
  404. struct deferred_message_t {
  405. const ap_message id;
  406. uint16_t interval_ms;
  407. uint16_t last_sent_ms; // from AP_HAL::millis16()
  408. } deferred_message[2] = {
  409. { MSG_HEARTBEAT, },
  410. { MSG_NEXT_PARAM, },
  411. };
  412. // returns index of id in deferred_message[] or -1 if not present
  413. int8_t get_deferred_message_index(const ap_message id) const;
  414. // returns index of a message in deferred_message[] which should
  415. // be sent (or -1 if none to send at the moment)
  416. int8_t deferred_message_to_send_index();
  417. // cache of which deferred message should be sent next:
  418. int8_t next_deferred_message_to_send_cache = -1;
  419. struct deferred_message_bucket_t {
  420. Bitmask<MSG_LAST> ap_message_ids;
  421. uint16_t interval_ms;
  422. uint16_t last_sent_ms; // from AP_HAL::millis16()
  423. };
  424. deferred_message_bucket_t deferred_message_bucket[10];
  425. static const uint8_t no_bucket_to_send = -1;
  426. static const ap_message no_message_to_send = (ap_message)-1;
  427. uint8_t sending_bucket_id = no_bucket_to_send;
  428. Bitmask<MSG_LAST> bucket_message_ids_to_send;
  429. ap_message next_deferred_bucket_message_to_send();
  430. void find_next_bucket_to_send();
  431. void remove_message_from_bucket(int8_t bucket, ap_message id);
  432. // bitmask of IDs the code has spontaneously decided it wants to
  433. // send out. Examples include HEARTBEAT (gcs_send_heartbeat)
  434. Bitmask<MSG_LAST> pushed_ap_message_ids;
  435. // returns true if it is OK to send a message while we are in
  436. // delay callback. In particular, when we are doing sensor init
  437. // we still send heartbeats.
  438. bool should_send_message_in_delay_callback(const ap_message id) const;
  439. // if true is returned, interval will contain the default interval for id
  440. bool get_default_interval_for_ap_message(const ap_message id, uint16_t &interval) const;
  441. // if true is returned, interval will contain the default interval for id
  442. bool get_default_interval_for_mavlink_message_id(const uint32_t mavlink_message_id, uint16_t &interval) const;
  443. // returns an interval in milliseconds for any ap_message in stream id
  444. uint16_t get_interval_for_stream(GCS_MAVLINK::streams id) const;
  445. // set an inverval for a specific mavlink message. Returns false
  446. // on failure (typically because there is no mapping from that
  447. // mavlink ID to an ap_message)
  448. bool set_mavlink_message_id_interval(const uint32_t mavlink_id,
  449. const uint16_t interval_ms);
  450. // map a mavlink ID to an ap_message which, if passed to
  451. // try_send_message, will cause a mavlink message with that id to
  452. // be emitted. Returns MSG_LAST if no such mapping exists.
  453. ap_message mavlink_id_to_ap_message_id(const uint32_t mavlink_id) const;
  454. // set the interval at which an ap_message should be emitted (in ms)
  455. bool set_ap_message_interval(enum ap_message id, uint16_t interval_ms);
  456. // call set_ap_message_interval for each entry in a stream,
  457. // the interval being based on the stream's rate
  458. void initialise_message_intervals_for_stream(GCS_MAVLINK::streams id);
  459. // call initialise_message_intervals_for_stream on every stream:
  460. void initialise_message_intervals_from_streamrates();
  461. // boolean that indicated that message intervals have been set
  462. // from streamrates:
  463. bool deferred_messages_initialised;
  464. // return interval deferred message bucket should be sent after.
  465. // When sending parameters and waypoints this may be longer than
  466. // the interval specified in "deferred"
  467. uint16_t get_reschedule_interval_ms(const deferred_message_bucket_t &deferred) const;
  468. bool do_try_send_message(const ap_message id);
  469. // time when we missed sending a parameter for GCS
  470. static uint32_t reserve_param_space_start_ms;
  471. // bitmask of what mavlink channels are active
  472. static uint8_t mavlink_active;
  473. // bitmask of what mavlink channels are private
  474. static uint8_t mavlink_private;
  475. // bitmask of what mavlink channels are streaming
  476. static uint8_t chan_is_streaming;
  477. // mavlink routing object
  478. static MAVLink_routing routing;
  479. struct pending_param_request {
  480. mavlink_channel_t chan;
  481. int16_t param_index;
  482. char param_name[AP_MAX_NAME_SIZE+1];
  483. };
  484. struct pending_param_reply {
  485. mavlink_channel_t chan;
  486. float value;
  487. enum ap_var_type p_type;
  488. int16_t param_index;
  489. uint16_t count;
  490. char param_name[AP_MAX_NAME_SIZE+1];
  491. };
  492. // queue of pending parameter requests and replies
  493. static ObjectBuffer<pending_param_request> param_requests;
  494. static ObjectBuffer<pending_param_reply> param_replies;
  495. // have we registered the IO timer callback?
  496. static bool param_timer_registered;
  497. // IO timer callback for parameters
  498. void param_io_timer(void);
  499. uint8_t send_parameter_async_replies();
  500. void send_distance_sensor(const class AP_RangeFinder_Backend *sensor, const uint8_t instance) const;
  501. virtual bool handle_guided_request(AP_Mission::Mission_Command &cmd) = 0;
  502. virtual void handle_change_alt_request(AP_Mission::Mission_Command &cmd) = 0;
  503. void handle_common_mission_message(const mavlink_message_t &msg);
  504. void handle_vicon_position_estimate(const mavlink_message_t &msg);
  505. void handle_vision_position_estimate(const mavlink_message_t &msg);
  506. void handle_global_vision_position_estimate(const mavlink_message_t &msg);
  507. void handle_att_pos_mocap(const mavlink_message_t &msg);
  508. void handle_common_vision_position_estimate_data(const uint64_t usec,
  509. const float x,
  510. const float y,
  511. const float z,
  512. const float roll,
  513. const float pitch,
  514. const float yaw,
  515. const uint16_t payload_size);
  516. void log_vision_position_estimate_data(const uint64_t usec,
  517. const uint32_t corrected_msec,
  518. const float x,
  519. const float y,
  520. const float z,
  521. const float roll,
  522. const float pitch,
  523. const float yaw);
  524. void lock_channel(const mavlink_channel_t chan, bool lock);
  525. /*
  526. correct an offboard timestamp in microseconds to a local time
  527. since boot in milliseconds
  528. */
  529. uint32_t correct_offboard_timestamp_usec_to_ms(uint64_t offboard_usec, uint16_t payload_size);
  530. mavlink_signing_t signing;
  531. static mavlink_signing_streams_t signing_streams;
  532. static uint32_t last_signing_save_ms;
  533. static StorageAccess _signing_storage;
  534. static bool signing_key_save(const struct SigningKey &key);
  535. static bool signing_key_load(struct SigningKey &key);
  536. void load_signing_key(void);
  537. bool signing_enabled(void) const;
  538. static void save_signing_timestamp(bool force_save_now);
  539. // alternative protocol handler support
  540. struct {
  541. GCS_MAVLINK::protocol_handler_fn_t handler;
  542. uint32_t last_mavlink_ms;
  543. uint32_t last_alternate_ms;
  544. bool active;
  545. } alternative;
  546. JitterCorrection lag_correction;
  547. // we cache the current location and send it even if the AHRS has
  548. // no idea where we are:
  549. struct Location global_position_current_loc;
  550. void zero_rc_outputs();
  551. uint8_t last_tx_seq;
  552. uint16_t send_packet_count;
  553. #if GCS_DEBUG_SEND_MESSAGE_TIMINGS
  554. struct {
  555. uint32_t longest_time_us;
  556. ap_message longest_id;
  557. uint32_t no_space_for_message;
  558. uint16_t statustext_last_sent_ms;
  559. uint32_t behind;
  560. uint32_t out_of_time;
  561. uint16_t fnbts_maxtime;
  562. uint32_t max_retry_deferred_body_us;
  563. uint8_t max_retry_deferred_body_type;
  564. } try_send_message_stats;
  565. uint16_t max_slowdown_ms;
  566. #endif
  567. uint32_t last_mavlink_stats_logged;
  568. };
  569. /// @class GCS
  570. /// @brief global GCS object
  571. class GCS
  572. {
  573. public:
  574. GCS() {
  575. if (_singleton == nullptr) {
  576. _singleton = this;
  577. } else {
  578. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  579. // this is a serious problem, but we don't need to kill a
  580. // real vehicle
  581. AP_HAL::panic("GCS must be singleton");
  582. #endif
  583. }
  584. };
  585. static class GCS *get_singleton() {
  586. return _singleton;
  587. }
  588. virtual uint32_t custom_mode() const = 0;
  589. virtual MAV_TYPE frame_type() const = 0;
  590. virtual const char* frame_string() const { return nullptr; }
  591. void send_to_active_channels(uint32_t msgid, const char *pkt);
  592. void send_text(MAV_SEVERITY severity, const char *fmt, ...) FMT_PRINTF(3, 4);
  593. void send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_list);
  594. virtual void send_statustext(MAV_SEVERITY severity, uint8_t dest_bitmask, const char *text);
  595. void service_statustext(void);
  596. virtual GCS_MAVLINK *chan(const uint8_t ofs) = 0;
  597. virtual const GCS_MAVLINK *chan(const uint8_t ofs) const = 0;
  598. // return the number of valid GCS objects
  599. uint8_t num_gcs() const { return _num_gcs; };
  600. void send_message(enum ap_message id);
  601. void send_mission_item_reached_message(uint16_t mission_index);
  602. void send_named_float(const char *name, float value) const;
  603. void send_parameter_value(const char *param_name,
  604. ap_var_type param_type,
  605. float param_value);
  606. static MissionItemProtocol_Waypoints *_missionitemprotocol_waypoints;
  607. static MissionItemProtocol_Rally *_missionitemprotocol_rally;
  608. MissionItemProtocol *get_prot_for_mission_type(const MAV_MISSION_TYPE mission_type) const;
  609. void try_send_queued_message_for_type(MAV_MISSION_TYPE type);
  610. void update_send();
  611. void update_receive();
  612. // minimum amount of time (in microseconds) that must remain in
  613. // the main scheduler loop before we are allowed to send any
  614. // mavlink messages. We want to prioritise the main flight
  615. // control loop over communications
  616. virtual uint16_t min_loop_time_remaining_for_message_send_us() const {
  617. return 200;
  618. }
  619. void setup_console();
  620. void setup_uarts();
  621. bool out_of_time() const;
  622. // frsky backend
  623. AP_Frsky_Telem *frsky;
  624. #if !HAL_MINIMIZE_FEATURES
  625. // Devo backend
  626. AP_DEVO_Telem devo_telemetry;
  627. #endif
  628. // install an alternative protocol handler
  629. bool install_alternative_protocol(mavlink_channel_t chan, GCS_MAVLINK::protocol_handler_fn_t handler);
  630. // get the VFR_HUD throttle
  631. int16_t get_hud_throttle(void) const { return num_gcs()>0?chan(0)->vfr_hud_throttle():0; }
  632. // update uart pass-thru
  633. void update_passthru();
  634. void get_sensor_status_flags(uint32_t &present, uint32_t &enabled, uint32_t &health);
  635. virtual bool vehicle_initialised() const { return true; }
  636. virtual bool simple_input_active() const { return false; }
  637. virtual bool supersimple_input_active() const { return false; }
  638. protected:
  639. virtual GCS_MAVLINK *new_gcs_mavlink_backend(GCS_MAVLINK_Parameters &params,
  640. AP_HAL::UARTDriver &uart) = 0;
  641. uint32_t control_sensors_present;
  642. uint32_t control_sensors_enabled;
  643. uint32_t control_sensors_health;
  644. virtual void update_vehicle_sensor_status_flags() {}
  645. GCS_MAVLINK_Parameters chan_parameters[MAVLINK_COMM_NUM_BUFFERS];
  646. uint8_t _num_gcs;
  647. GCS_MAVLINK *_chan[MAVLINK_COMM_NUM_BUFFERS];
  648. private:
  649. static GCS *_singleton;
  650. void create_gcs_mavlink_backend(GCS_MAVLINK_Parameters &params,
  651. AP_HAL::UARTDriver &uart);
  652. struct statustext_t {
  653. uint8_t bitmask;
  654. mavlink_statustext_t msg;
  655. };
  656. void update_sensor_status_flags();
  657. #if HAL_MEM_CLASS <= HAL_MEM_CLASS_192 || CONFIG_HAL_BOARD == HAL_BOARD_SITL
  658. static const uint8_t _status_capacity = 5;
  659. #else
  660. static const uint8_t _status_capacity = 30;
  661. #endif
  662. // a lock for the statustext queue, to make it safe to use send_text()
  663. // from multiple threads
  664. HAL_Semaphore _statustext_sem;
  665. // queue of outgoing statustext messages
  666. ObjectArray<statustext_t> _statustext_queue{_status_capacity};
  667. // true if we have already allocated protocol objects:
  668. bool initialised_missionitemprotocol_objects;
  669. // handle passthru between two UARTs
  670. struct {
  671. bool enabled;
  672. bool timer_installed;
  673. AP_HAL::UARTDriver *port1;
  674. AP_HAL::UARTDriver *port2;
  675. uint32_t start_ms;
  676. uint32_t last_ms;
  677. uint32_t last_port1_data_ms;
  678. uint8_t timeout_s;
  679. HAL_Semaphore sem;
  680. } _passthru;
  681. // timer called to implement pass-thru
  682. void passthru_timer();
  683. };
  684. GCS &gcs();