PX4 V1.13.0版本bug
px4 tailsitter的几个突出问题
问题1
在使用 px4 v1.12.3 版本,开发 vtol tailsitter(尾座式垂直起降)过程中,出现了定高模式四旋翼状态下逻辑混乱的问题,但是没能够查明原因,因此考虑使用新版本代码解决这一问题,因此换用 v1.13.0 解决问题,测试使用 v1.13.0 后,确实解决了逻辑混乱的问题,但是新版本又出现了新的问题,空速计参数无法获得,但是换回原来的代码版本又变得正常,在 cuav v5 nano 和 nora 上分别复现了这个问题,确认并非硬件问题导致,是代码版本升级导致。
解决方法
在新版本代码中,多出了一些传感器参数,其中包括了多个空速传感器驱动的开关,其中就包含了雷迅自带的空速计版本,参数如下
将其从默认的关闭状态 0,调整为开启状态 1,就能成功检测空速信息了,留此文件记录。
另外新版本mavlink消息不回传servo_out_raw,无法在地面上在线调试pwm输出,有点麻烦,不知道怎么能打开这部分功能。
问题2及其解决方法
在vtol tailsitter模式下,在旋翼状态下使用时候姿态角是正常状态,而在切换到固定翼模式后,在地面站的姿态角显示会保留原来的角度,如果是90度倾转,也就是默认的转动方法,处于欧拉角描述姿态的奇点上,姿态难以看懂,但是程序内部处理是正常的,姿态和指令都会做转换,指令部分转换如下
if (_is_tailsitter) {
/* vehicle is a tailsitter, we need to modify the estimated attitude for fw mode
*
* Since the VTOL airframe is initialized as a multicopter we need to
* modify the estimated attitude for the fixed wing operation.
* Since the neutral position of the vehicle in fixed wing mode is -90 degrees rotated around
* the pitch axis compared to the neutral position of the vehicle in multicopter mode
* we need to swap the roll and the yaw axis (1st and 3rd column) in the rotation matrix.
* Additionally, in order to get the correct sign of the pitch, we need to multiply
* the new x axis of the rotation matrix with -1
*
* original: modified:
*
* Rxx Ryx Rzx -Rzx Ryx Rxx
* Rxy Ryy Rzy -Rzy Ryy Rxy
* Rxz Ryz Rzz -Rzz Ryz Rxz
* */
matrix::Dcmf R_adapted = R; //modified rotation matrix
/* move z to x */
R_adapted(0, 0) = R(0, 2);
R_adapted(1, 0) = R(1, 2);
R_adapted(2, 0) = R(2, 2);
/* move x to z */
R_adapted(0, 2) = R(0, 0);
R_adapted(1, 2) = R(1, 0);
R_adapted(2, 2) = R(2, 0);
/* change direction of pitch (convert to right handed system) */
R_adapted(0, 0) = -R_adapted(0, 0);
R_adapted(1, 0) = -R_adapted(1, 0);
R_adapted(2, 0) = -R_adapted(2, 0);
/* fill in new attitude data */
R = R_adapted;
/* lastly, roll- and yawspeed have to be swaped */
float helper = rollspeed;
rollspeed = -yawspeed;
yawspeed = helper;
}
在上述代码中通过旋转矩阵的调整完成了姿态角指令的切换,因此在实际的控制器操作过程中使用的指令值是正常的,也就是控制器具备正常的setpoint。
在实际操作过程,usb和数传发送使用的mavlink消息内容不同,我测试1.13.0版本代码usb发回来的数据是会进行自动切换的,因此重新查看代码,发现px4是通过int Mavlink::configure_streams_to_default(const char *configure_single_stream)
来进行数据传输判断用何种方式传输的,传输内容和频率也都在该函数下规定,当使用常规数传时,会进入case MAVLINK_MODE_NORMAL:
判断,按照指定频率发送所需消息,再通过地面站mavlink inspector
功能能够查看地面站接收到的所有mavlink消息内容,可以找到usb连接和telemetry连接的姿态发送区别在于是否ATTITUDE_QUATERNION
消息,将这个消息内容使得数传也同步发送就能解决姿态角混乱的问题了,用类似的方法也能解决上面发送servo_out_raw
的问题,暂时这样记录,后面详细整理下px4中mavlink消息的发送方法再更新这部分内容
常规数传发送内容:
case MAVLINK_MODE_NORMAL:
configure_stream_local("ADSB_VEHICLE", unlimited_rate);
configure_stream_local("ALTITUDE", 1.0f);
configure_stream_local("ATTITUDE", 15.0f);
configure_stream_local("ATTITUDE_TARGET", 2.0f);
configure_stream_local("BATTERY_STATUS", 0.5f);
configure_stream_local("CAMERA_IMAGE_CAPTURED", unlimited_rate);
configure_stream_local("COLLISION", unlimited_rate);
configure_stream_local("DISTANCE_SENSOR", 0.5f);
configure_stream_local("EFI_STATUS", 2.0f);
configure_stream_local("ESC_INFO", 1.0f);
configure_stream_local("ESC_STATUS", 1.0f);
configure_stream_local("ESTIMATOR_STATUS", 0.5f);
configure_stream_local("EXTENDED_SYS_STATE", 1.0f);
configure_stream_local("GLOBAL_POSITION_INT", 5.0f);
configure_stream_local("GIMBAL_DEVICE_ATTITUDE_STATUS", 1.0f);
configure_stream_local("GIMBAL_MANAGER_STATUS", 0.5f);
configure_stream_local("GIMBAL_DEVICE_SET_ATTITUDE", 5.0f);
configure_stream_local("GPS2_RAW", 1.0f);
configure_stream_local("GPS_GLOBAL_ORIGIN", 0.1f);
configure_stream_local("GPS_RAW_INT", 1.0f);
configure_stream_local("GPS_STATUS", 1.0f);
configure_stream_local("HOME_POSITION", 0.5f);
configure_stream_local("LOCAL_POSITION_NED", 1.0f);
configure_stream_local("NAV_CONTROLLER_OUTPUT", 1.0f);
configure_stream_local("OBSTACLE_DISTANCE", 1.0f);
configure_stream_local("ORBIT_EXECUTION_STATUS", 2.0f);
configure_stream_local("PING", 0.1f);
configure_stream_local("POSITION_TARGET_GLOBAL_INT", 1.0f);
configure_stream_local("POSITION_TARGET_LOCAL_NED", 1.5f);
configure_stream_local("RAW_RPM", 2.0f);
configure_stream_local("RC_CHANNELS", 5.0f);
configure_stream_local("SERVO_OUTPUT_RAW_0", 1.0f);
configure_stream_local("SYS_STATUS", 1.0f);
configure_stream_local("UTM_GLOBAL_POSITION", 0.5f);
configure_stream_local("VFR_HUD", 4.0f);
configure_stream_local("VIBRATION", 0.1f);
configure_stream_local("WIND_COV", 0.5f);
使用usb时候发送的内容
case MAVLINK_MODE_CONFIG: // USB
// Note: streams requiring low latency come first
configure_stream_local("TIMESYNC", 10.0f);
configure_stream_local("CAMERA_TRIGGER", unlimited_rate);
configure_stream_local("LOCAL_POSITION_NED", 30.0f);
configure_stream_local("DISTANCE_SENSOR", 10.0f);
configure_stream_local("MOUNT_ORIENTATION", 10.0f);
configure_stream_local("ODOMETRY", 30.0f);
configure_stream_local("ACTUATOR_CONTROL_TARGET0", 30.0f);
configure_stream_local("ADSB_VEHICLE", unlimited_rate);
configure_stream_local("ALTITUDE", 10.0f);
configure_stream_local("ATTITUDE", 50.0f);
configure_stream_local("ATTITUDE_QUATERNION", 50.0f);
configure_stream_local("ATTITUDE_TARGET", 8.0f);
configure_stream_local("BATTERY_STATUS", 0.5f);
configure_stream_local("CAMERA_IMAGE_CAPTURED", unlimited_rate);
configure_stream_local("COLLISION", unlimited_rate);
configure_stream_local("EFI_STATUS", 10.0f);
configure_stream_local("ESC_INFO", 10.0f);
configure_stream_local("ESC_STATUS", 10.0f);
configure_stream_local("ESTIMATOR_STATUS", 5.0f);
configure_stream_local("EXTENDED_SYS_STATE", 2.0f);
configure_stream_local("GLOBAL_POSITION_INT", 10.0f);
configure_stream_local("GPS2_RAW", unlimited_rate);
configure_stream_local("GPS_GLOBAL_ORIGIN", 1.0f);
configure_stream_local("GPS_RAW_INT", unlimited_rate);
configure_stream_local("GPS_STATUS", 1.0f);
configure_stream_local("HIGHRES_IMU", 50.0f);
configure_stream_local("HOME_POSITION", 0.5f);
configure_stream_local("MANUAL_CONTROL", 5.0f);
configure_stream_local("NAV_CONTROLLER_OUTPUT", 10.0f);
configure_stream_local("OPTICAL_FLOW_RAD", 10.0f);
configure_stream_local("ORBIT_EXECUTION_STATUS", 5.0f);
configure_stream_local("PING", 1.0f);
configure_stream_local("POSITION_TARGET_GLOBAL_INT", 10.0f);
configure_stream_local("RAW_RPM", 5.0f);
configure_stream_local("RC_CHANNELS", 10.0f);
configure_stream_local("SCALED_IMU", 25.0f);
configure_stream_local("SCALED_IMU2", 25.0f);
configure_stream_local("SCALED_IMU3", 25.0f);
configure_stream_local("SERVO_OUTPUT_RAW_0", 20.0f);
configure_stream_local("SERVO_OUTPUT_RAW_1", 20.0f);
configure_stream_local("SYS_STATUS", 1.0f);
configure_stream_local("SYSTEM_TIME", 1.0f);
configure_stream_local("UTM_GLOBAL_POSITION", 1.0f);
configure_stream_local("VFR_HUD", 20.0f);
configure_stream_local("VIBRATION", 2.5f);
configure_stream_local("WIND_COV", 10.0f);