mirror of https://github.com/ArduPilot/ardupilot
Rover: set-position-target message processing only checks xy fields
This commit is contained in:
parent
9299943347
commit
1d92ec5724
|
@ -86,9 +86,9 @@ enum mode {
|
|||
#define MASK_LOG_IMU_RAW (1UL<<19)
|
||||
|
||||
// for mavlink SET_POSITION_TARGET messages
|
||||
#define MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE ((1<<0) | (1<<1) | (1<<2))
|
||||
#define MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE ((1<<3) | (1<<4) | (1<<5))
|
||||
#define MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE ((1<<6) | (1<<7) | (1<<8))
|
||||
#define MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE ((1<<0) | (1<<1))
|
||||
#define MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE ((1<<3) | (1<<4))
|
||||
#define MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE ((1<<6) | (1<<7))
|
||||
#define MAVLINK_SET_POS_TYPE_MASK_FORCE (1<<9)
|
||||
#define MAVLINK_SET_POS_TYPE_MASK_YAW_IGNORE (1<<10)
|
||||
#define MAVLINK_SET_POS_TYPE_MASK_YAW_RATE_IGNORE (1<<11)
|
||||
|
|
Loading…
Reference in New Issue