2014-12-16 19:28:56 -04:00
|
|
|
//
|
|
|
|
// Simple test for the GCS_MAVLink routing
|
|
|
|
//
|
|
|
|
|
2015-08-11 03:28:46 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include <GCS_MAVLink/GCS.h>
|
2015-10-20 10:05:13 -03:00
|
|
|
#include <GCS_MAVLink/GCS_MAVLink.h>
|
2019-06-19 21:46:01 -03:00
|
|
|
#include <GCS_MAVLink/GCS_Dummy.h>
|
2019-04-04 07:49:44 -03:00
|
|
|
#include <AP_Common/AP_FWVersion.h>
|
2018-12-10 03:56:32 -04:00
|
|
|
#include <AP_SerialManager/AP_SerialManager.h>
|
2014-12-16 19:28:56 -04:00
|
|
|
|
2017-04-13 08:33:33 -03:00
|
|
|
void setup();
|
|
|
|
void loop();
|
|
|
|
|
2015-10-16 17:22:11 -03:00
|
|
|
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
2014-12-16 19:28:56 -04:00
|
|
|
|
2018-12-10 03:56:32 -04:00
|
|
|
AP_SerialManager _serialmanager;
|
2019-06-19 21:46:01 -03:00
|
|
|
GCS_Dummy _gcs;
|
2014-12-16 19:28:56 -04:00
|
|
|
|
|
|
|
extern mavlink_system_t mavlink_system;
|
|
|
|
|
2018-12-10 03:56:32 -04:00
|
|
|
const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
|
2014-12-16 19:28:56 -04:00
|
|
|
AP_GROUPEND
|
|
|
|
};
|
|
|
|
|
|
|
|
static MAVLink_routing routing;
|
2023-09-29 01:10:03 -03:00
|
|
|
static mavlink_status_t status;
|
2014-12-16 19:28:56 -04:00
|
|
|
|
|
|
|
void setup(void)
|
|
|
|
{
|
2016-05-30 07:05:00 -03:00
|
|
|
hal.console->printf("routing test startup...");
|
2020-02-11 21:01:17 -04:00
|
|
|
gcs().init();
|
2018-12-10 03:56:32 -04:00
|
|
|
gcs().setup_console();
|
2014-12-16 19:28:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
void loop(void)
|
|
|
|
{
|
|
|
|
uint16_t err_count = 0;
|
|
|
|
|
|
|
|
// incoming heartbeat
|
|
|
|
mavlink_message_t msg;
|
|
|
|
mavlink_heartbeat_t heartbeat = {0};
|
|
|
|
|
2023-09-29 01:10:03 -03:00
|
|
|
mavlink_msg_heartbeat_encode_status(3, 1, &status, &msg, &heartbeat);
|
2014-12-16 19:28:56 -04:00
|
|
|
|
2023-03-05 19:44:55 -04:00
|
|
|
GCS_MAVLINK *dummy_link = gcs().chan(0);
|
|
|
|
|
|
|
|
if (!routing.check_and_forward(*dummy_link, msg)) {
|
2014-12-16 19:28:56 -04:00
|
|
|
hal.console->printf("heartbeat should be processed locally\n");
|
|
|
|
err_count++;
|
|
|
|
}
|
|
|
|
|
|
|
|
// incoming non-targetted message
|
|
|
|
mavlink_attitude_t attitude = {0};
|
2023-09-29 01:10:03 -03:00
|
|
|
mavlink_msg_attitude_encode_status(3, 1, &status, &msg, &attitude);
|
2023-03-05 19:44:55 -04:00
|
|
|
if (!routing.check_and_forward(*dummy_link, msg)) {
|
2014-12-16 19:28:56 -04:00
|
|
|
hal.console->printf("attitude should be processed locally\n");
|
|
|
|
err_count++;
|
|
|
|
}
|
|
|
|
|
2016-05-12 13:51:11 -03:00
|
|
|
// incoming targeted message for someone else
|
2014-12-16 19:28:56 -04:00
|
|
|
mavlink_param_set_t param_set = {0};
|
|
|
|
param_set.target_system = mavlink_system.sysid+1;
|
|
|
|
param_set.target_component = mavlink_system.compid;
|
2023-09-29 01:10:03 -03:00
|
|
|
mavlink_msg_param_set_encode_status(3, 1, &status, &msg, ¶m_set);
|
2023-03-05 19:44:55 -04:00
|
|
|
if (routing.check_and_forward(*dummy_link, msg)) {
|
2014-12-16 19:28:56 -04:00
|
|
|
hal.console->printf("param set 1 should not be processed locally\n");
|
|
|
|
err_count++;
|
|
|
|
}
|
|
|
|
|
2016-05-12 13:51:11 -03:00
|
|
|
// incoming targeted message for us
|
2014-12-16 19:28:56 -04:00
|
|
|
param_set.target_system = mavlink_system.sysid;
|
|
|
|
param_set.target_component = mavlink_system.compid;
|
2023-09-29 01:10:03 -03:00
|
|
|
mavlink_msg_param_set_encode_status(3, 1, &status, &msg, ¶m_set);
|
2023-03-05 19:44:55 -04:00
|
|
|
if (!routing.check_and_forward(*dummy_link, msg)) {
|
2014-12-16 19:28:56 -04:00
|
|
|
hal.console->printf("param set 2 should be processed locally\n");
|
|
|
|
err_count++;
|
|
|
|
}
|
|
|
|
|
2016-05-12 13:51:11 -03:00
|
|
|
// incoming targeted message for our system, but other compid
|
2014-12-16 19:28:56 -04:00
|
|
|
// should be processed locally
|
|
|
|
param_set.target_system = mavlink_system.sysid;
|
|
|
|
param_set.target_component = mavlink_system.compid+1;
|
2023-09-29 01:10:03 -03:00
|
|
|
mavlink_msg_param_set_encode_status(3, 1, &status, &msg, ¶m_set);
|
2023-03-05 19:44:55 -04:00
|
|
|
if (!routing.check_and_forward(*dummy_link, msg)) {
|
2014-12-16 19:28:56 -04:00
|
|
|
hal.console->printf("param set 3 should be processed locally\n");
|
|
|
|
err_count++;
|
|
|
|
}
|
|
|
|
|
|
|
|
// incoming broadcast message should be processed locally
|
|
|
|
param_set.target_system = 0;
|
|
|
|
param_set.target_component = mavlink_system.compid+1;
|
2023-09-29 01:10:03 -03:00
|
|
|
mavlink_msg_param_set_encode_status(3, 1, &status, &msg, ¶m_set);
|
2023-03-05 19:44:55 -04:00
|
|
|
if (!routing.check_and_forward(*dummy_link, msg)) {
|
2014-12-16 19:28:56 -04:00
|
|
|
hal.console->printf("param set 4 should be processed locally\n");
|
|
|
|
err_count++;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (err_count == 0) {
|
|
|
|
hal.console->printf("All OK\n");
|
|
|
|
}
|
|
|
|
hal.scheduler->delay(1000);
|
|
|
|
}
|
|
|
|
|
|
|
|
AP_HAL_MAIN();
|