APM:Libraries
routing.cpp
Go to the documentation of this file.
1 //
2 // Simple test for the GCS_MAVLink routing
3 //
4 
5 #include <AP_HAL/AP_HAL.h>
6 #include <GCS_MAVLink/GCS.h>
8 
9 void setup();
10 void loop();
11 
13 
14 
15 const AP_FWVersion fwver
16 {
17  major: 3,
18  minor: 1,
19  patch: 4,
20  fw_type: FIRMWARE_VERSION_TYPE_DEV,
21  fw_string: "routing example"
22 };
23 
25 {
26 
27 public:
28 
29 protected:
30 
31  uint32_t telem_delay() const override { return 0; }
32  Compass *get_compass() const override { return nullptr; };
33  AP_Mission *get_mission() override { return nullptr; }
34  AP_Rally *get_rally() const override { return nullptr; }
35  AP_Camera *get_camera() const override { return nullptr; };
36  uint8_t sysid_my_gcs() const override { return 1; }
37  bool set_mode(uint8_t mode) override { return false; };
38  const AP_FWVersion &get_fwver() const override { return fwver; }
39 
40  // dummy information:
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; }
43  uint32_t custom_mode() const override { return 3; } // magic number
44  MAV_STATE system_status() const override { return MAV_STATE_CALIBRATING; }
45 
46 private:
47 
48  void handleMessage(mavlink_message_t * msg) { }
49  bool handle_guided_request(AP_Mission::Mission_Command &cmd) override { return false ; }
51  bool try_send_message(enum ap_message id) override { return false; }
52 
53 };
54 
55 
56 static const uint8_t num_gcs = MAVLINK_COMM_NUM_BUFFERS;
58 
59 extern mavlink_system_t mavlink_system;
60 
63 };
64 
66 
67 void setup(void)
68 {
69  hal.console->printf("routing test startup...");
70  gcs_link[0].init(hal.uartA, MAVLINK_COMM_0);
71 }
72 
73 void loop(void)
74 {
75  uint16_t err_count = 0;
76 
77  // incoming heartbeat
78  mavlink_message_t msg;
79  mavlink_heartbeat_t heartbeat = {0};
80 
81  mavlink_msg_heartbeat_encode(3, 1, &msg, &heartbeat);
82 
83  if (!routing.check_and_forward(MAVLINK_COMM_0, &msg)) {
84  hal.console->printf("heartbeat should be processed locally\n");
85  err_count++;
86  }
87 
88  // incoming non-targetted message
89  mavlink_attitude_t attitude = {0};
90  mavlink_msg_attitude_encode(3, 1, &msg, &attitude);
91  if (!routing.check_and_forward(MAVLINK_COMM_0, &msg)) {
92  hal.console->printf("attitude should be processed locally\n");
93  err_count++;
94  }
95 
96  // incoming targeted message for someone else
97  mavlink_param_set_t param_set = {0};
98  param_set.target_system = mavlink_system.sysid+1;
99  param_set.target_component = mavlink_system.compid;
100  mavlink_msg_param_set_encode(3, 1, &msg, &param_set);
101  if (routing.check_and_forward(MAVLINK_COMM_0, &msg)) {
102  hal.console->printf("param set 1 should not be processed locally\n");
103  err_count++;
104  }
105 
106  // incoming targeted message for us
107  param_set.target_system = mavlink_system.sysid;
108  param_set.target_component = mavlink_system.compid;
109  mavlink_msg_param_set_encode(3, 1, &msg, &param_set);
110  if (!routing.check_and_forward(MAVLINK_COMM_0, &msg)) {
111  hal.console->printf("param set 2 should be processed locally\n");
112  err_count++;
113  }
114 
115  // incoming targeted message for our system, but other compid
116  // should be processed locally
117  param_set.target_system = mavlink_system.sysid;
118  param_set.target_component = mavlink_system.compid+1;
119  mavlink_msg_param_set_encode(3, 1, &msg, &param_set);
120  if (!routing.check_and_forward(MAVLINK_COMM_0, &msg)) {
121  hal.console->printf("param set 3 should be processed locally\n");
122  err_count++;
123  }
124 
125  // incoming broadcast message should be processed locally
126  param_set.target_system = 0;
127  param_set.target_component = mavlink_system.compid+1;
128  mavlink_msg_param_set_encode(3, 1, &msg, &param_set);
129  if (!routing.check_and_forward(MAVLINK_COMM_0, &msg)) {
130  hal.console->printf("param set 4 should be processed locally\n");
131  err_count++;
132  }
133 
134  if (err_count == 0) {
135  hal.console->printf("All OK\n");
136  }
137  hal.scheduler->delay(1000);
138 }
139 
140 AP_HAL_MAIN();
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: routing.cpp:12
Object managing Rally Points.
Definition: AP_Rally.h:37
void setup()
Definition: routing.cpp:67
AP_HAL::UARTDriver * console
Definition: HAL.h:110
Interface definition for the various Ground Control System.
Object managing Mission.
Definition: AP_Mission.h:45
ap_message
Definition: GCS.h:37
const AP_FWVersion fwver
Definition: routing.cpp:16
int param_set(param_t param, const void *val)
Definition: px4_param.cpp:37
virtual void delay(uint16_t ms)=0
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
mavlink_system_t mavlink_system
MAVLink system definition.
Definition: GCS_MAVLink.cpp:42
static GCS_MAVLINK_routing gcs_link[MAVLINK_COMM_NUM_BUFFERS]
Definition: routing.cpp:57
const HAL & get_HAL()
static const uint8_t num_gcs
Definition: routing.cpp:56
AP_HAL::UARTDriver * uartA
Definition: HAL.h:100
void loop()
Definition: routing.cpp:73
AP_HAL_MAIN()
#define AP_GROUPEND
Definition: AP_Param.h:121
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114