forked from Archive/PX4-Autopilot
mavlink: streams/COMMAND_LONG don't send internal vehicle_commands
This commit is contained in:
parent
f8a090e85e
commit
e387f302f9
|
@ -74,7 +74,16 @@ private:
|
|||
_vehicle_command_sub.get_last_generation());
|
||||
}
|
||||
|
||||
if (!cmd.from_external && cmd.command < vehicle_command_s::VEHICLE_CMD_PX4_INTERNAL_START) {
|
||||
// mavlink mavlink commands are <= UINT16_MAX
|
||||
const bool px4_internal_cmd = (cmd.command >= vehicle_command_s::VEHICLE_CMD_PX4_INTERNAL_START);
|
||||
|
||||
// internal commands
|
||||
const bool target_system_internal = (cmd.target_system == _mavlink->get_system_id())
|
||||
&& (cmd.target_component == _mavlink->get_component_id())
|
||||
&& (cmd.source_system == cmd.target_system)
|
||||
&& (cmd.source_component == cmd.target_component);
|
||||
|
||||
if (!cmd.from_external && !px4_internal_cmd && !target_system_internal) {
|
||||
PX4_DEBUG("sending command %d to %d/%d", cmd.command, cmd.target_system, cmd.target_component);
|
||||
|
||||
MavlinkCommandSender::instance().handle_vehicle_command(cmd, _mavlink->get_channel());
|
||||
|
|
Loading…
Reference in New Issue