20 fw_type: FIRMWARE_VERSION_TYPE_DEV,
21 fw_string:
"routing example" 37 bool set_mode(uint8_t mode)
override {
return false; };
41 MAV_TYPE
frame_type()
const override {
return MAV_TYPE_FIXED_WING; }
42 MAV_MODE
base_mode()
const override {
return (MAV_MODE)MAV_MODE_FLAG_CUSTOM_MODE_ENABLED; }
44 MAV_STATE
system_status()
const override {
return MAV_STATE_CALIBRATING; }
70 gcs_link[0].
init(hal.
uartA, MAVLINK_COMM_0);
75 uint16_t err_count = 0;
78 mavlink_message_t msg;
79 mavlink_heartbeat_t heartbeat = {0};
81 mavlink_msg_heartbeat_encode(3, 1, &msg, &heartbeat);
84 hal.
console->
printf(
"heartbeat should be processed locally\n");
89 mavlink_attitude_t attitude = {0};
90 mavlink_msg_attitude_encode(3, 1, &msg, &attitude);
92 hal.
console->
printf(
"attitude should be processed locally\n");
100 mavlink_msg_param_set_encode(3, 1, &msg, ¶m_set);
102 hal.
console->
printf(
"param set 1 should not be processed locally\n");
109 mavlink_msg_param_set_encode(3, 1, &msg, ¶m_set);
111 hal.
console->
printf(
"param set 2 should be processed locally\n");
119 mavlink_msg_param_set_encode(3, 1, &msg, ¶m_set);
121 hal.
console->
printf(
"param set 3 should be processed locally\n");
126 param_set.target_system = 0;
128 mavlink_msg_param_set_encode(3, 1, &msg, ¶m_set);
130 hal.
console->
printf(
"param set 4 should be processed locally\n");
134 if (err_count == 0) {
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Object managing Rally Points.
MAV_TYPE frame_type() const override
MAVLink transport control class.
Compass * get_compass() const override
AP_HAL::UARTDriver * console
void init(AP_HAL::UARTDriver *port, mavlink_channel_t mav_chan)
Interface definition for the various Ground Control System.
MAV_STATE system_status() const override
uint32_t custom_mode() const override
void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override
AP_Mission * get_mission() override
int param_set(param_t param, const void *val)
MAV_MODE base_mode() const override
uint32_t telem_delay() const override
AP_Camera * get_camera() const override
virtual void delay(uint16_t ms)=0
void handleMessage(mavlink_message_t *msg)
virtual void printf(const char *,...) FMT_PRINTF(2
static MAVLink_routing routing
mavlink_system_t mavlink_system
MAVLink system definition.
AP_Rally * get_rally() const override
const AP_FWVersion & get_fwver() const override
bool check_and_forward(mavlink_channel_t in_channel, const mavlink_message_t *msg)
static GCS_MAVLINK_routing gcs_link[MAVLINK_COMM_NUM_BUFFERS]
uint8_t sysid_my_gcs() const override
static const struct AP_Param::GroupInfo var_info[]
static const uint8_t num_gcs
AP_HAL::UARTDriver * uartA
bool handle_guided_request(AP_Mission::Mission_Command &cmd) override
bool set_mode(uint8_t mode) override
bool try_send_message(enum ap_message id) override
AP_HAL::Scheduler * scheduler
#define MAVLINK_COMM_NUM_BUFFERS