APM:Libraries
GCS.cpp
Go to the documentation of this file.
1 #include "GCS.h"
2 
3 extern const AP_HAL::HAL& hal;
4 
5 /*
6  send a text message to all GCS
7  */
8 void GCS::send_text(MAV_SEVERITY severity, const char *fmt, ...)
9 {
10  char text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {};
11  va_list arg_list;
12  va_start(arg_list, fmt);
13  hal.util->vsnprintf((char *)text, sizeof(text)-1, fmt, arg_list);
14  va_end(arg_list);
15  text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN] = 0;
17 }
18 
19 #define FOR_EACH_ACTIVE_CHANNEL(methodcall) \
20  do { \
21  for (uint8_t i=0; i<num_gcs(); i++) { \
22  if (!chan(i).initialised) { \
23  continue; \
24  } \
25  if (!(GCS_MAVLINK::active_channel_mask() & (1 << (chan(i).get_chan()-MAVLINK_COMM_0)))) { \
26  continue; \
27  } \
28  chan(i).methodcall; \
29  } \
30  } while (0)
31 
32 void GCS::send_named_float(const char *name, float value) const
33 {
35 }
36 
37 void GCS::send_home() const
38 {
40 }
41 
43 {
45 }
46 
47 /*
48  install an alternative protocol handler. This allows another
49  protocol to take over the link if MAVLink goes idle. It is used to
50  allow for the AP_BLHeli pass-thru protocols to run on hal.uartA
51  */
52 bool GCS::install_alternative_protocol(mavlink_channel_t c, GCS_MAVLINK::protocol_handler_fn_t handler)
53 {
54  if (c >= num_gcs()) {
55  return false;
56  }
57  if (chan(c).alternative.handler) {
58  // already have one installed - we may need to add support for
59  // multiple alternative handlers
60  return false;
61  }
62  chan(c).alternative.handler = handler;
63  return true;
64 }
65 
66 
67 #undef FOR_EACH_ACTIVE_CHANNEL
virtual uint8_t num_gcs() const =0
Interface definition for the various Ground Control System.
#define FOR_EACH_ACTIVE_CHANNEL(methodcall)
Definition: GCS.cpp:19
AP_HAL::Util * util
Definition: HAL.h:115
const char * name
Definition: BusTest.cpp:11
void send_home() const
Definition: GCS.cpp:37
int vsnprintf(char *str, size_t size, const char *format, va_list ap)
Definition: Util.cpp:53
virtual GCS_MAVLINK & chan(const uint8_t ofs)=0
virtual void send_statustext(MAV_SEVERITY severity, uint8_t dest_bitmask, const char *text)
const char * fmt
Definition: Printf.cpp:14
void send_named_float(const char *name, float value) const
Definition: GCS.cpp:32
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Definition: GCS.cpp:8
void send_ekf_origin() const
Definition: GCS.cpp:42
float value
bool install_alternative_protocol(mavlink_channel_t chan, GCS_MAVLINK::protocol_handler_fn_t handler)
Definition: GCS.cpp:52