菜单

Mavlink消息与Mavros话题(位置控制&姿态控制相关)

下载

Mavlink消息与Mavros话题(位置控制&姿态控制相关)

本篇梳理一下使用PX4飞控时,与位置控制&姿态控制相关的Mavlink消息与Mavros话题

参考资料

设置本地位置目标值 - SET_POSITION_TARGET_LOCAL_NED (#84)

  • 本地位置控制目标值(包括位置、速度、加速度、偏航角等设置值,可组合设置)
/
SET_POSITION_TARGET_LOCAL_NED
  • setpoint_raw.cpp中会订阅相关ROS话题,并打包成这个Mavlink消息发送至PX4费控,订阅话题如下:
    • 本地位置设定值:mavros/setpoint_raw/local,话题类型为mavros_msgs::PositionTarget
  • ROS话题赋值参考,type_mask是一个二进制数,请根据实际情况设置
C 复制代码
    mavros_msgs::PositionTarget local_setpoint;
    local_setpoint.header.stamp = ros::Time::now();
    // 这里虽然赋值是FRAME_LOCAL_NED,但是Mavros会当成ENU进行处理
    local_setpoint.coordinate_frame = mavros_msgs::PositionTarget::FRAME_LOCAL_NED;
    local_setpoint.type_mask = xx;
    local_setpoint.position.x = 0;
    local_setpoint.position.y = 0;
    local_setpoint.position.z = 0;
    local_setpoint.velocity.x = 0;
    local_setpoint.velocity.y = 0;
    local_setpoint.velocity.z = 0;
    local_setpoint.acceleration_or_force.x = 0;
    local_setpoint.acceleration_or_force.y = 0;
    local_setpoint.acceleration_or_force.z = 0;
    local_setpoint.yaw = 0;
    local_setpoint.yaw_rate = 0;
    px4_setpoint_local_pub.publish(local_setpoint);
  • 常见的控制组合:
    • 期望位置+偏航
    • 期望位置+偏航速度
    • 期望速度+偏航
    • 期望速度+偏航速度
    • 期望加速度+偏航
    • 期望加速度+偏航速度
  • 如果想验证本消息是否正确发送给PX4,可以通过订阅mavros/setpoint_raw/target_local话题确认,该话题对应的是POSITION_TARGET_LOCAL_NED (#85)消息

设置全局位置目标值 - SET_POSITION_TARGET_GLOBAL_INT (#86)

  • 全局位置控制目标值(包括经纬高、速度、加速度、偏航角等设置值,可组合设置)
/
SET_POSITION_TARGET_GLOBAL_INT
  • setpoint_raw.cpp中会订阅相关ROS话题,并打包成这个Mavlink消息发送至PX4费控,订阅话题如下:
    • 本地位置设定值:mavros/setpoint_raw/global,话题类型为mavros_msgs::GlobalPositionTarget
  • ROS话题赋值参考,type_mask是一个二进制数,请根据实际情况设置
C 复制代码
    mavros_msgs::GlobalPositionTarget global_setpoint;
    global_setpoint.header.stamp = ros::Time::now();
    global_setpoint.coordinate_frame = mavros_msgs::GlobalPositionTarget::FRAME_GLOBAL_REL_ALT; // 相对高度
    global_setpoint.type_mask = TypeMask::GLOBAL_POSITION;
    global_setpoint.latitude = 0;
    global_setpoint.longitude = 0;
    global_setpoint.altitude = 0;
    global_setpoint.velocity.x = 0;
    global_setpoint.velocity.y = 0;
    global_setpoint.velocity.z = 0;
    global_setpoint.acceleration_or_force.x = 0;
    global_setpoint.acceleration_or_force.y = 0;
    global_setpoint.acceleration_or_force.z = 0;
    global_setpoint.yaw = 0;
    global_setpoint.yaw_rate = 0;
    px4_setpoint_global_pub.publish(global_setpoint);
  • 常见的控制组合:
    • 期望经纬高+偏航
  • 如果想验证本消息是否正确发送给PX4,可以通过订阅mavros/setpoint_raw/target_global话题确认,该话题对应的是POSITION_TARGET_GLOBAL_INT (#87)消息

设置姿态目标值 - SET_ATTITUDE_TARGET (#82)

  • 姿态控制目标值(包括姿态、角速度、推力)
/
SET_ATTITUDE_TARGET
  • setpoint_raw.cpp中会订阅相关ROS话题,并打包成这个Mavlink消息发送至PX4费控,订阅话题如下:
    • 本地位置设定值:mavros/setpoint_raw/attitude,话题类型为mavros_msgs::AttitudeTarget
  • ROS话题赋值参考,type_mask是一个二进制数,请根据实际情况设置
C 复制代码
    mavros_msgs::AttitudeTarget att_setpoint;
    // Mappings: If any of these bits are set, the corresponding input should be ignored:
    // bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude
    //  0b00000111;
    att_setpoint.type_mask = mavros_msgs::AttitudeTarget::IGNORE_ROLL_RATE |
                             mavros_msgs::AttitudeTarget::IGNORE_PITCH_RATE |
                             mavros_msgs::AttitudeTarget::IGNORE_YAW_RATE;

    Eigen::Vector3d att_des;
    att_des << u_att(0), u_att(1), u_att(2);
    Eigen::Quaterniond q_des = quaternion_from_rpy(att_des);
    att_setpoint.orientation.x = q_des.x();
    att_setpoint.orientation.y = q_des.y();
    att_setpoint.orientation.z = q_des.z();
    att_setpoint.orientation.w = q_des.w();
    att_setpoint.thrust = u_att(3);
    px4_setpoint_attitude_pub.publish(att_setpoint);
  • 常见的控制组合:
    • 期望姿态+推力(三轴合力,取值范围:0-1)
    • 期望角速度+推力(三轴合力,取值范围:0-1)
  • 如果想验证本消息是否正确发送给PX4,可以通过订阅mavros/setpoint_raw/target_attitude话题确认,该话题对应的是ATTITUDE_TARGET(#83)消息
上一个
Mavlink消息与Mavros话题(GPS相关)
下一个
PX4二次开发
最近修改: 2025-10-20