本篇梳理一下使用PX4飞控时,与位置控制&姿态控制相关的Mavlink消息与Mavros话题
mavros/setpoint_raw/local,话题类型为mavros_msgs::PositionTargettype_mask是一个二进制数,请根据实际情况设置 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);
mavros/setpoint_raw/target_local话题确认,该话题对应的是POSITION_TARGET_LOCAL_NED (#85)消息
mavros/setpoint_raw/global,话题类型为mavros_msgs::GlobalPositionTargettype_mask是一个二进制数,请根据实际情况设置 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);
mavros/setpoint_raw/target_global话题确认,该话题对应的是POSITION_TARGET_GLOBAL_INT (#87)消息
mavros/setpoint_raw/attitude,话题类型为mavros_msgs::AttitudeTargettype_mask是一个二进制数,请根据实际情况设置 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);
mavros/setpoint_raw/target_attitude话题确认,该话题对应的是ATTITUDE_TARGET(#83)消息