mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: use mavlink_XXX_encode_status() in example code
This commit is contained in:
parent
be01fcfdfd
commit
ac3f4f0c5e
|
@ -24,6 +24,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
|
||||||
};
|
};
|
||||||
|
|
||||||
static MAVLink_routing routing;
|
static MAVLink_routing routing;
|
||||||
|
static mavlink_status_t status;
|
||||||
|
|
||||||
void setup(void)
|
void setup(void)
|
||||||
{
|
{
|
||||||
|
@ -40,7 +41,7 @@ void loop(void)
|
||||||
mavlink_message_t msg;
|
mavlink_message_t msg;
|
||||||
mavlink_heartbeat_t heartbeat = {0};
|
mavlink_heartbeat_t heartbeat = {0};
|
||||||
|
|
||||||
mavlink_msg_heartbeat_encode(3, 1, &msg, &heartbeat);
|
mavlink_msg_heartbeat_encode_status(3, 1, &status, &msg, &heartbeat);
|
||||||
|
|
||||||
GCS_MAVLINK *dummy_link = gcs().chan(0);
|
GCS_MAVLINK *dummy_link = gcs().chan(0);
|
||||||
|
|
||||||
|
@ -51,7 +52,7 @@ void loop(void)
|
||||||
|
|
||||||
// incoming non-targetted message
|
// incoming non-targetted message
|
||||||
mavlink_attitude_t attitude = {0};
|
mavlink_attitude_t attitude = {0};
|
||||||
mavlink_msg_attitude_encode(3, 1, &msg, &attitude);
|
mavlink_msg_attitude_encode_status(3, 1, &status, &msg, &attitude);
|
||||||
if (!routing.check_and_forward(*dummy_link, msg)) {
|
if (!routing.check_and_forward(*dummy_link, msg)) {
|
||||||
hal.console->printf("attitude should be processed locally\n");
|
hal.console->printf("attitude should be processed locally\n");
|
||||||
err_count++;
|
err_count++;
|
||||||
|
@ -61,7 +62,7 @@ void loop(void)
|
||||||
mavlink_param_set_t param_set = {0};
|
mavlink_param_set_t param_set = {0};
|
||||||
param_set.target_system = mavlink_system.sysid+1;
|
param_set.target_system = mavlink_system.sysid+1;
|
||||||
param_set.target_component = mavlink_system.compid;
|
param_set.target_component = mavlink_system.compid;
|
||||||
mavlink_msg_param_set_encode(3, 1, &msg, ¶m_set);
|
mavlink_msg_param_set_encode_status(3, 1, &status, &msg, ¶m_set);
|
||||||
if (routing.check_and_forward(*dummy_link, msg)) {
|
if (routing.check_and_forward(*dummy_link, msg)) {
|
||||||
hal.console->printf("param set 1 should not be processed locally\n");
|
hal.console->printf("param set 1 should not be processed locally\n");
|
||||||
err_count++;
|
err_count++;
|
||||||
|
@ -70,7 +71,7 @@ void loop(void)
|
||||||
// incoming targeted message for us
|
// incoming targeted message for us
|
||||||
param_set.target_system = mavlink_system.sysid;
|
param_set.target_system = mavlink_system.sysid;
|
||||||
param_set.target_component = mavlink_system.compid;
|
param_set.target_component = mavlink_system.compid;
|
||||||
mavlink_msg_param_set_encode(3, 1, &msg, ¶m_set);
|
mavlink_msg_param_set_encode_status(3, 1, &status, &msg, ¶m_set);
|
||||||
if (!routing.check_and_forward(*dummy_link, msg)) {
|
if (!routing.check_and_forward(*dummy_link, msg)) {
|
||||||
hal.console->printf("param set 2 should be processed locally\n");
|
hal.console->printf("param set 2 should be processed locally\n");
|
||||||
err_count++;
|
err_count++;
|
||||||
|
@ -80,7 +81,7 @@ void loop(void)
|
||||||
// should be processed locally
|
// should be processed locally
|
||||||
param_set.target_system = mavlink_system.sysid;
|
param_set.target_system = mavlink_system.sysid;
|
||||||
param_set.target_component = mavlink_system.compid+1;
|
param_set.target_component = mavlink_system.compid+1;
|
||||||
mavlink_msg_param_set_encode(3, 1, &msg, ¶m_set);
|
mavlink_msg_param_set_encode_status(3, 1, &status, &msg, ¶m_set);
|
||||||
if (!routing.check_and_forward(*dummy_link, msg)) {
|
if (!routing.check_and_forward(*dummy_link, msg)) {
|
||||||
hal.console->printf("param set 3 should be processed locally\n");
|
hal.console->printf("param set 3 should be processed locally\n");
|
||||||
err_count++;
|
err_count++;
|
||||||
|
@ -89,7 +90,7 @@ void loop(void)
|
||||||
// incoming broadcast message should be processed locally
|
// incoming broadcast message should be processed locally
|
||||||
param_set.target_system = 0;
|
param_set.target_system = 0;
|
||||||
param_set.target_component = mavlink_system.compid+1;
|
param_set.target_component = mavlink_system.compid+1;
|
||||||
mavlink_msg_param_set_encode(3, 1, &msg, ¶m_set);
|
mavlink_msg_param_set_encode_status(3, 1, &status, &msg, ¶m_set);
|
||||||
if (!routing.check_and_forward(*dummy_link, msg)) {
|
if (!routing.check_and_forward(*dummy_link, msg)) {
|
||||||
hal.console->printf("param set 4 should be processed locally\n");
|
hal.console->printf("param set 4 should be processed locally\n");
|
||||||
err_count++;
|
err_count++;
|
||||||
|
|
Loading…
Reference in New Issue