Browse Source

Cleaned up target system handling for some commands

sbg
Lorenz Meier 9 years ago
parent
commit
ebeb9eba4b
  1. 39
      src/modules/mavlink/mavlink_receiver.cpp
  2. 2
      src/modules/mavlink/mavlink_receiver.h

39
src/modules/mavlink/mavlink_receiver.cpp

@ -279,29 +279,37 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg)
_mavlink->set_has_received_messages(true); _mavlink->set_has_received_messages(true);
} }
void bool
MavlinkReceiver::handle_message_command_long(mavlink_message_t *msg) MavlinkReceiver::evaluate_target_ok(int command, int target_system, int target_component)
{ {
/* command */
mavlink_command_long_t cmd_mavlink;
mavlink_msg_command_long_decode(msg, &cmd_mavlink);
/* evaluate if this system should accept this command */ /* evaluate if this system should accept this command */
bool target_ok; bool target_ok = false;
switch (cmd_mavlink.command) { switch (command) {
case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES: case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES:
/* broadcast */ /* broadcast and ignore component */
target_ok = (cmd_mavlink.target_system == 0); target_ok = (target_system == 0) || (target_system == mavlink_system.sysid);
break; break;
default: default:
target_ok = (cmd_mavlink.target_system == mavlink_system.sysid); target_ok = (target_system == mavlink_system.sysid) && ((target_component == mavlink_system.compid)
|| (target_component == MAV_COMP_ID_ALL));
break; break;
} }
if (target_ok && ((cmd_mavlink.target_component == mavlink_system.compid) return target_ok;
|| (cmd_mavlink.target_component == MAV_COMP_ID_ALL))) { }
void
MavlinkReceiver::handle_message_command_long(mavlink_message_t *msg)
{
/* command */
mavlink_command_long_t cmd_mavlink;
mavlink_msg_command_long_decode(msg, &cmd_mavlink);
bool target_ok = evaluate_target_ok(cmd_mavlink.command, cmd_mavlink.target_system, cmd_mavlink.target_component);
if (target_ok) {
//check for MAVLINK terminate command //check for MAVLINK terminate command
if (cmd_mavlink.command == MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN && ((int)cmd_mavlink.param1) == 3) { if (cmd_mavlink.command == MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN && ((int)cmd_mavlink.param1) == 3) {
/* This is the link shutdown command, terminate mavlink */ /* This is the link shutdown command, terminate mavlink */
@ -362,8 +370,9 @@ MavlinkReceiver::handle_message_command_int(mavlink_message_t *msg)
mavlink_command_int_t cmd_mavlink; mavlink_command_int_t cmd_mavlink;
mavlink_msg_command_int_decode(msg, &cmd_mavlink); mavlink_msg_command_int_decode(msg, &cmd_mavlink);
if (cmd_mavlink.target_system == mavlink_system.sysid && ((cmd_mavlink.target_component == mavlink_system.compid) bool target_ok = evaluate_target_ok(cmd_mavlink.command, cmd_mavlink.target_system, cmd_mavlink.target_component);
|| (cmd_mavlink.target_component == MAV_COMP_ID_ALL))) {
if (target_ok) {
//check for MAVLINK terminate command //check for MAVLINK terminate command
if (cmd_mavlink.command == MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN && ((int)cmd_mavlink.param1) == 3) { if (cmd_mavlink.command == MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN && ((int)cmd_mavlink.param1) == 3) {
/* This is the link shutdown command, terminate mavlink */ /* This is the link shutdown command, terminate mavlink */

2
src/modules/mavlink/mavlink_receiver.h

@ -161,6 +161,8 @@ private:
*/ */
int decode_switch_pos_n(uint16_t buttons, unsigned sw); int decode_switch_pos_n(uint16_t buttons, unsigned sw);
bool evaluate_target_ok(int command, int target_system, int target_component);
mavlink_status_t status; mavlink_status_t status;
struct vehicle_local_position_s hil_local_pos; struct vehicle_local_position_s hil_local_pos;
struct vehicle_land_detected_s hil_land_detector; struct vehicle_land_detected_s hil_land_detector;

Loading…
Cancel
Save