mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
Support additional payload commands and let commander ignore them
This commit is contained in:
parent
19fa79dcb1
commit
4af4e4e1e5
@ -615,6 +615,11 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s
|
||||
case VEHICLE_CMD_PREFLIGHT_CALIBRATION:
|
||||
case VEHICLE_CMD_PREFLIGHT_SET_SENSOR_OFFSETS:
|
||||
case VEHICLE_CMD_PREFLIGHT_STORAGE:
|
||||
case VEHICLE_CMD_CUSTOM_0:
|
||||
case VEHICLE_CMD_CUSTOM_1:
|
||||
case VEHICLE_CMD_CUSTOM_2:
|
||||
case VEHICLE_CMD_PAYLOAD_PREPARE_DEPLOY:
|
||||
case VEHICLE_CMD_PAYLOAD_CONTROL_DEPLOY:
|
||||
/* ignore commands that handled in low prio loop */
|
||||
break;
|
||||
|
||||
|
||||
@ -1,9 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
|
||||
* Author: @author Thomas Gubler <thomasgubler@student.ethz.ch>
|
||||
* @author Julian Oes <joes@student.ethz.ch>
|
||||
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
* Copyright (C) 2012-2014 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
@ -37,6 +34,10 @@
|
||||
/**
|
||||
* @file vehicle_command.h
|
||||
* Definition of the vehicle command uORB topic.
|
||||
*
|
||||
* @author Thomas Gubler <thomasgubler@student.ethz.ch>
|
||||
* @author Julian Oes <joes@student.ethz.ch>
|
||||
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
*/
|
||||
|
||||
#ifndef TOPIC_VEHICLE_COMMAND_H_
|
||||
@ -52,6 +53,9 @@
|
||||
* but can contain additional ones.
|
||||
*/
|
||||
enum VEHICLE_CMD {
|
||||
VEHICLE_CMD_CUSTOM_0 = 0, /* test command */
|
||||
VEHICLE_CMD_CUSTOM_1 = 1, /* test command */
|
||||
VEHICLE_CMD_CUSTOM_2 = 2, /* test command */
|
||||
VEHICLE_CMD_NAV_WAYPOINT = 16, /* Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| */
|
||||
VEHICLE_CMD_NAV_LOITER_UNLIM = 17, /* Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
|
||||
VEHICLE_CMD_NAV_LOITER_TURNS = 18, /* Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
|
||||
@ -87,7 +91,8 @@ enum VEHICLE_CMD {
|
||||
VEHICLE_CMD_MISSION_START = 300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */
|
||||
VEHICLE_CMD_COMPONENT_ARM_DISARM = 400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */
|
||||
VEHICLE_CMD_START_RX_PAIR = 500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */
|
||||
VEHICLE_CMD_ENUM_END = 501, /* | */
|
||||
VEHICLE_CMD_PAYLOAD_PREPARE_DEPLOY = 30001, /**< Prepare a payload deployment in the flight plan */
|
||||
VEHICLE_CMD_PAYLOAD_CONTROL_DEPLOY = 30002 /**< Control a pre-programmed payload deployment */
|
||||
};
|
||||
|
||||
/**
|
||||
@ -115,8 +120,8 @@ struct vehicle_command_s {
|
||||
float param2; /**< Parameter 2, as defined by MAVLink VEHICLE_CMD enum. */
|
||||
float param3; /**< Parameter 3, as defined by MAVLink VEHICLE_CMD enum. */
|
||||
float param4; /**< Parameter 4, as defined by MAVLink VEHICLE_CMD enum. */
|
||||
float param5; /**< Parameter 5, as defined by MAVLink VEHICLE_CMD enum. */
|
||||
float param6; /**< Parameter 6, as defined by MAVLink VEHICLE_CMD enum. */
|
||||
double param5; /**< Parameter 5, as defined by MAVLink VEHICLE_CMD enum. */
|
||||
double param6; /**< Parameter 6, as defined by MAVLink VEHICLE_CMD enum. */
|
||||
float param7; /**< Parameter 7, as defined by MAVLink VEHICLE_CMD enum. */
|
||||
enum VEHICLE_CMD command; /**< Command ID, as defined MAVLink by VEHICLE_CMD enum. */
|
||||
uint8_t target_system; /**< System which should execute the command */
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user