1. 消息定义
查看消息定义
rosmsg show mavros_msgs/PositionTarget
内容如下
uint8 FRAME_LOCAL_NED=1
uint8 FRAME_LOCAL_OFFSET_NED=7
uint8 FRAME_BODY_NED=8
uint8 FRAME_BODY_OFFSET_NED=9
uint16 IGNORE_PX=1
uint16 IGNORE_PY=2
uint16 IGNORE_PZ=4
uint16 IGNORE_VX=8
uint16 IGNORE_VY=16
uint16 IGNORE_VZ=32
uint16 IGNORE_AFX=64
uint16 IGNORE_AFY=128
uint16 IGNORE_AFZ=256
uint16 FORCE=512
uint16 IGNORE_YAW=1024
uint16 IGNORE_YAW_RATE=2048
std_msgs/Header header
uint32 seq
time stamp
string frame_id
uint8 coordinate_frame
uint16 type_mask
geometry_msgs/Point position
float64 x
float64 y
float64 z
geometry_msgs/Vector3 velocity
float64 x
float64 y
float64 z
geometry_msgs/Vector3 acceleration_or_force
float64 x
float64 y
float64 z
float32 yaw
float32 yaw_rate
2. 发布消息步骤
需要注意两个关键字段 coordinate_frame 和 type_mask
2.1 coordinate_frame
在动捕或其他外部定位系统下,通常应该设置为 1。这样可以控制无人机在局部坐标系(惯性系)下的位置/速度/加速度/偏航等。
Frame 编号 | Frame 名称 | 原点 | 特点 | 应用场景 |
---|---|---|---|---|
1 |
FRAME_LOCAL_NED |
起飞点(固定):1. GPS 定位:起飞点的全球坐标(WGS84)。2. 外部视觉或动捕定位:起飞点在全局坐标系中的定义(如外部定位系统的世界坐标系原点)。 | 全局绝对坐标系,与定位系统的世界坐标系一致。支持 GPS 和外部定位(动捕、视觉等)。 | 全局导航,例如路径规划、航点飞行;支持 GPS 或动捕等精确定位的任务。 |
7 |
FRAME_LOCAL_OFFSET_NED |
当前点(动态) | 相对当前位置的局部坐标系 | 临时导航,例如相对当前位置偏移目标 |
8 |
FRAME_BODY_NED |
当前点(动态),方向随姿态变化 | 基于机体姿态的相对运动控制 | 方向相关任务,例如朝机头方向加速或转弯 |
9 |
FRAME_BODY_OFFSET_NED |
当前点(动态),方向随姿态变化 | 基于机体相对偏移的动态控制 | 临时机体运动控制 |
2.2 type_mask
标志位取值 | 名称 | 作用 |
---|---|---|
1 | IGNORE_PX | 0: 会考虑 position.x (目标位置的 X 坐标)字段, 1: 忽略 position.x 字段 |
2 | IGNORE_PY | 0: 会考虑 position.y (目标位置的 Y 坐标)字段, 1: 忽略 position.y 字段 |
4 | IGNORE_PZ | 0: 会考虑 position.z (目标位置的 Z 坐标)字段, 1: 忽略 position.z 字段 |
8 | IGNORE_VX | 0: 会考虑 velocity.x (目标速度的 X 方向分量)字段, 1: 忽略 velocity.x 字段 |
16 | IGNORE_VY | 0: 会考虑 velocity.y (目标速度的 Y 方向分量)字段, 1: 忽略 velocity.y 字段 |
32 | IGNORE_VZ | 0: 会考虑 velocity.z (目标速度的 Z 方向分量)字段, 1: 忽略 velocity.z 字段 |
64 | IGNORE_AFX | 0: 会考虑 acceleration_or_force.x (目标 X 方向加速度或力)字段, 1: 忽略 acceleration_or_force.x 字段 |
128 | IGNORE_AFY | 0: 会考虑 acceleration_or_force.y (目标 Y 方向加速度或力)字段, 1: 忽略 acceleration_or_force.y 字段 |
256 | IGNORE_AFZ | 0: 会考虑 acceleration_or_force.z (目标 Z 方向加速度或力)字段, 1: 忽略 acceleration_or_force.z 字段 |
512 | FORCE | 0: 视 acceleration_or_force (加速度或力)为加速度值, 1: 视 acceleration_or_force 为力值 |
1024 | IGNORE_YAW | 0: 会考虑 yaw (目标航向角)字段, 1: 忽略 yaw 字段 |
2048 | IGNORE_YAW_RATE | 0: 会考虑 yaw_rate (目标航向角速率)字段, 1: 忽略 yaw_rate 字段 |
例如
- 定点控制时,掩码应该设置为
0b111111111000
,忽略除了PX PY PZ
以外的指令,如果想额外控制机头方向,可以设置为0b101111111000
。 - 将无人机当做一阶积分器模型,给定速度指令,则设置为
0b111111000111
。同理,想要额外给定偏航角,参考定点控制,将对应忽略位置为 0。 - 将无人机当做二阶积分器模型,给定加速度指令,则设置
0b110000111111
。注意除了AFX AFY AFZ 设置为 0 表示不忽略以外,还需要将 FORCE 置为 0。否则,PX4 将误认为 AFX AFY AFZ 是推力矢量。 - 特别的,如果只是给XY轴的速度或加速度命令,Z轴采用PX4的算法定高。可以设置为
0b110100111011
。 - Python 中可以通过如下方法,选择多个位设置为 1,C++ 写法类似。
from mavros_msgs.msg import PositionTarget
msg = PositionTarget()
msg.type_mask = PositionTarget.IGNORE_PX | PositionTarget.IGNORE_PY | PositionTarget.IGNORE_PZ
# PX PY PZ 被忽略了,等同于
# msg.type_mask = 0b000000000111
# msg.type_mask = 7 (1+2+4)
根据掩码,设置对应的 position
,velocity
,acceleration_or_force
,yaw
和 yaw_rate
字段即可。