PX4中的mavlink

2023-05-16

简介

px4与地面站的通信协议是mavlink,对于其消息格式的介绍看这里和这里。
需要注意几点:

  • 不光是px4与qgroundcontrol通信通过mavlink,有一些sensor也支持mavlink。
  • mavlink在github中是一个单独的仓库,通过git submodule的方式集成到了px4中。
  • mavlink协议本身并不复杂,用户也不同关心底层的实现(发送、接收、校验、打包、解包)等,只需要提供消息格式(在mavlink中选择现成的or自定义)、通信周期就可以了。

我主要关心几个问题:

  1. mavlink是如何编译的?
  2. mavlink有哪些参数?
  3. mavlink是如何启动的?
  4. px4中都有哪些现有的mavlink消息?px4中都有哪些现有的mavlink消息?
  5. 如何定义新的mavlink消息?
  6. mavlink是怎么配置硬件设备的?
  7. mavlink是怎么把uorb的消息打包的?
  8. mavlink是怎么定时发送消息的?
  9. mavlink是怎么接收消息的?
  10. mavlink是怎么解析接收消息的?

mavlink是如何编译的?

在linux下,看posix_sitl_default.cmake中的modules/mavlink

mavlink有哪些参数?

在ROMFS/px4fmu_common/init.d/rcS中:

set MAVLINK_F default
set MAVLINK_COMPANION_DEVICE /dev/ttyS2
set MAV_TYPE none

mavlink是如何启动的?

  • 在nuttx下
    见ROMFS/px4fmu_common/init.d/rcS
# Start mavlink streams.
#
sh /etc/init.d/rc.mavlink 

...
#
# Boot is complete, inform MAVLink app(s) that the system is now fully up and running.
#
mavlink boot_complete

rc.mavlink中的内容:

if ! ver hwcmp AEROFC_V1
then
	# Start MAVLink
	mavlink start -r 800000 -d /dev/ttyACM0 -m config -x
fi
...
if [ "x${MAVLINK_F}" == xdefault ]
then
	# Normal mode, use baudrate 57600 (default) and data rate 1000 bytes/s
	set MAVLINK_F "-r 1200 -f"
	
	# Use ttyS1 for MAVLink on FMUv4 in addition to ttyS0 (debug)
	if ver hwcmp PX4FMU_V4
	then
		set MAVLINK_F "-r 1200 -d /dev/ttyS1"
		# Start MAVLink on Wifi (ESP8266 port)
		mavlink start -r 20000 -b 921600 -d /dev/ttyS0
	fi

	# Use ttyS3 (TELEM4) for MAVLink on FMUv5 in addition to ttyS1 (TELEM1) and ttyS2 (TELEM2)
	if ver hwcmp PX4FMU_V5
	then
		mavlink start -r 2000 -b 57600 -d /dev/ttyS3
	fi
fi

其中,ver是px4的指令,介绍见这里。Source: systemcmds/ver,
Tool to print various version information。
mavlink start后面的-r表示rate(通信周期),-b表示波特率,-d表示端口。

  • 在linux下
    见init.d-posix/rcS
# 启动mavlink,和GCS连接
# GCS link
# -r表示rate,-s表示stream_name,-u表示network_port
mavlink start -x -u $udp_gcs_port_local -r 4000000
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u $udp_gcs_port_local
mavlink stream -r 50 -s LOCAL_POSITION_NED -u $udp_gcs_port_local
mavlink stream -r 50 -s GLOBAL_POSITION_INT -u $udp_gcs_port_local
mavlink stream -r 50 -s ATTITUDE -u $udp_gcs_port_local
mavlink stream -r 50 -s ATTITUDE_QUATERNION -u $udp_gcs_port_local
mavlink stream -r 50 -s ATTITUDE_TARGET -u $udp_gcs_port_local
mavlink stream -r 50 -s SERVO_OUTPUT_RAW_0 -u $udp_gcs_port_local
mavlink stream -r 20 -s RC_CHANNELS -u $udp_gcs_port_local
mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u $udp_gcs_port_local

# API/Offboard link
mavlink start -x -u $udp_offboard_port_local -r 4000000 -m onboard -o $udp_offboard_port_remote
...
mavlink boot_complete

上面用到了两个脚本:

  • mavlink start:启动mavlink,执行mavlink::start。
  • mavlink stream:添加mavlink command,执行mavlink::stream_command。POSITION_TARGET_LOCAL_NED等是common.xml中定义的消息。

px4中都有哪些现有的mavlink消息?

在px4的工程中,在Firmware/mavlink/include/mavlink/v2.0/message_definitions目录下,有如下的xml消息:
├── ardupilotmega.xml
├── ASLUAV.xml
├── autoquad.xml
├── common.xml
├── icarous.xml
├── matrixpilot.xml
├── minimal.xml
├── paparazzi.xml
├── python_array_test.xml
├── slugs.xml
├── standard.xml
├── test.xml
├── ualberta.xml
└── uAvionix.xml
且在目录的上一级,每个xml都有对应的文件夹,包括各自的.h文件(都是MAVLink comm protocol generated from xml)。
关于上述xml的解释,见https://mavlink.gitbooks.io/mavlink-devguide/en/messages/

  • 默认的消息
    在这些消息中,只有heartbeat是必须的(qgc需要据此判断连接是否正常),其他都是可选的。
    mavlink_main.cpp中_mode默认是MAVLINK_MODE_NORMAL。在mavlin_main.cpp中,有
	/* add default streams depending on mode */
	if (_mode != MAVLINK_MODE_IRIDIUM) {    //这里的Iridium应该是铱星通信系统

		/* HEARTBEAT is constant rate stream, rate never adjusted */
		configure_stream("HEARTBEAT", 1.0f);

		/* STATUSTEXT stream is like normal stream but gets messages from logbuffer instead of uORB */
		configure_stream("STATUSTEXT", 20.0f);

		/* COMMAND_LONG stream: use unlimited rate to send all commands */
		configure_stream("COMMAND_LONG");

	}
  • 默认的其他消息:
    在configure_streams_to_default中有:
	switch (_mode) {
	case MAVLINK_MODE_NORMAL:
		configure_stream_local("ADSB_VEHICLE", unlimited_rate);
		configure_stream_local("ALTITUDE", 1.0f);
		configure_stream_local("ATTITUDE", 20.0f);
		configure_stream_local("ATTITUDE_TARGET", 2.0f);
		configure_stream_local("CAMERA_IMAGE_CAPTURED", unlimited_rate);
		configure_stream_local("COLLISION", unlimited_rate);
		configure_stream_local("DEBUG", 1.0f);
		configure_stream_local("DEBUG_VECT", 1.0f);
		configure_stream_local("DISTANCE_SENSOR", 0.5f);
		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("GPS_RAW_INT", 1.0f);
		configure_stream_local("GPS2_RAW", 1.0f);
		configure_stream_local("HIGHRES_IMU", 1.5f);
		configure_stream_local("HOME_POSITION", 0.5f);
		configure_stream_local("LOCAL_POSITION_NED", 1.0f);
		configure_stream_local("NAMED_VALUE_FLOAT", 1.0f);
		configure_stream_local("NAV_CONTROLLER_OUTPUT", 1.5f);
		configure_stream_local("OPTICAL_FLOW_RAD", 1.0f);
		configure_stream_local("PING", 0.1f);
		configure_stream_local("POSITION_TARGET_LOCAL_NED", 1.5f);
		configure_stream_local("POSITION_TARGET_GLOBAL_INT", 1.5f);
		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("TRAJECTORY_REPRESENTATION_WAYPOINTS", 5.0f);
		configure_stream_local("VFR_HUD", 4.0f);
		configure_stream_local("VISION_POSITION_ESTIMATE", 1.0f);
		configure_stream_local("WIND_COV", 1.0f);
		break;
		//...
		default:
		ret = -1;
		break;
	}

如何定义新的mavlink消息?

  1. 首先要安装mavlink generator
  2. 定义一个数据结构,比如说msg/ca_trajectory.msg
  3. 根据上面的数据结构写对应的xml
  4. 用mavlink generator生成mavlink消息(一个包含.h的文件夹)

后两个过程在这里。

mavlink是怎么配置硬件设备的?

见mavlink在rcS中的启动脚本(上面论述过)。

mavlink是怎么把uorb的消息打包的?

  1. 最底层。添加mavlink的头文件和uorb消息到mavlink_messages.cpp,比如自己添加的一个ca_trajectory消息:
#include <uORB/topics/ca_trajectory.h>
#include <v1.0/custom_messages/mavlink_msg_ca_trajectory.h>

或者一个mavlink中的common消息:

mavlink_msg_attitude_target.h  //被common.h所include,common.h被mavlink.h所include

这个.h文件就是打包过的数据结构

MAVPACKED(
typedef struct __mavlink_attitude_target_t {
 uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
 float q[4]; /*<  Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)*/
 float body_roll_rate; /*< [rad/s] Body roll rate*/
 float body_pitch_rate; /*< [rad/s] Body pitch rate*/
 float body_yaw_rate; /*< [rad/s] Body yaw rate*/
 float thrust; /*<  Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)*/
 uint8_t type_mask; /*<  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 7: reserved, bit 8: attitude*/
}) mavlink_attitude_target_t;

而且还包含了打包函数(mavlink_msg_attitude_target_pack)、encode函数(调用pack函数)、发送函数(mavlink_msg_attitude_target_send_struct)、decode函数(mavlink_msg_attitude_target_decode,调用unpack函数)、upack函数等。
2. 在mavlink_messages.cpp中创建一个新的类(可以看到其他消息也是这样做的),继承自MavlinkStream。这个类包括send函数

bool send(const hrt_abstime t)
	{
		vehicle_attitude_setpoint_s att_sp;

		if (_att_sp_sub->update(&_att_sp_time, &att_sp)) {

			vehicle_rates_setpoint_s att_rates_sp = {};
			_att_rates_sp_sub->update(&att_rates_sp);

			mavlink_attitude_target_t msg = {};

			msg.time_boot_ms = att_sp.timestamp / 1000;

			if (att_sp.q_d_valid) {
				memcpy(&msg.q[0], &att_sp.q_d[0], sizeof(msg.q));

			} else {
				matrix::Quatf q = matrix::Eulerf(att_sp.roll_body, att_sp.pitch_body, att_sp.yaw_body);
				memcpy(&msg.q[0], q.data(), sizeof(msg.q));
			}

			msg.body_roll_rate = att_rates_sp.roll;
			msg.body_pitch_rate = att_rates_sp.pitch;
			msg.body_yaw_rate = att_rates_sp.yaw;

			msg.thrust = att_sp.thrust;

			mavlink_msg_attitude_target_send_struct(_mavlink->get_channel(), &msg);

			return true;
		}

		return false;
	}

可以看出,send函数等待uorb更新,并把uorb数据转为mavlink数据,并通过mavlink_msg_attitude_target_send_struct发送出去。
3. 附加流类streams_list的到mavlink_messages.cpp底部,这是因为streams_list包括了所有预先定义的mavlink消息,在执行create_mavlink_stream时,需要到streams_list中检查是否有定义。

static const StreamListItem streams_list[] = {
	StreamListItem(&MavlinkStreamHeartbeat::new_instance, &MavlinkStreamHeartbeat::get_name_static, &MavlinkStreamHeartbeat::get_id_static),
	StreamListItem(&MavlinkStreamStatustext::new_instance, &MavlinkStreamStatustext::get_name_static, &MavlinkStreamStatustext::get_id_static),
	StreamListItem(&MavlinkStreamCommandLong::new_instance, &MavlinkStreamCommandLong::get_name_static, &MavlinkStreamCommandLong::get_id_static),
	StreamListItem(&MavlinkStreamSysStatus::new_instance, &MavlinkStreamSysStatus::get_name_static, &MavlinkStreamSysStatus::get_id_static),
	StreamListItem(&MavlinkStreamHighresIMU::new_instance, &MavlinkStreamHighresIMU::get_name_static, &MavlinkStreamHighresIMU::get_id_static),
	StreamListItem(&MavlinkStreamScaledIMU::new_instance, &MavlinkStreamScaledIMU::get_name_static, &MavlinkStreamScaledIMU::get_id_static),
	StreamListItem(&MavlinkStreamScaledIMU2::new_instance, &MavlinkStreamScaledIMU2::get_name_static, &MavlinkStreamScaledIMU2::get_id_static),
	StreamListItem(&MavlinkStreamScaledIMU3::new_instance, &MavlinkStreamScaledIMU3::get_name_static, &MavlinkStreamScaledIMU3::get_id_static),
	StreamListItem(&MavlinkStreamAttitude::new_instance, &MavlinkStreamAttitude::get_name_static, &MavlinkStreamAttitude::get_id_static),
	StreamListItem(&MavlinkStreamAttitudeQuaternion::new_instance, &MavlinkStreamAttitudeQuaternion::get_name_static, &MavlinkStreamAttitudeQuaternion::get_id_static),
	StreamListItem(&MavlinkStreamVFRHUD::new_instance, &MavlinkStreamVFRHUD::get_name_static, &MavlinkStreamVFRHUD::get_id_static),
	StreamListItem(&MavlinkStreamGPSRawInt::new_instance, &MavlinkStreamGPSRawInt::get_name_static, &MavlinkStreamGPSRawInt::get_id_static),
	StreamListItem(&MavlinkStreamGPS2Raw::new_instance, &MavlinkStreamGPS2Raw::get_name_static, &MavlinkStreamGPS2Raw::get_id_static),
	StreamListItem(&MavlinkStreamSystemTime::new_instance, &MavlinkStreamSystemTime::get_name_static, &MavlinkStreamSystemTime::get_id_static),
	StreamListItem(&MavlinkStreamTimesync::new_instance, &MavlinkStreamTimesync::get_name_static, &MavlinkStreamTimesync::get_id_static),
	StreamListItem(&MavlinkStreamGlobalPositionInt::new_instance, &MavlinkStreamGlobalPositionInt::get_name_static, &MavlinkStreamGlobalPositionInt::get_id_static),
	StreamListItem(&MavlinkStreamLocalPositionNED::new_instance, &MavlinkStreamLocalPositionNED::get_name_static, &MavlinkStreamLocalPositionNED::get_id_static),
	StreamListItem(&MavlinkStreamVisionPositionEstimate::new_instance, &MavlinkStreamVisionPositionEstimate::get_name_static, &MavlinkStreamVisionPositionEstimate::get_id_static),
	StreamListItem(&MavlinkStreamLocalPositionNEDCOV::new_instance, &MavlinkStreamLocalPositionNEDCOV::get_name_static, &MavlinkStreamLocalPositionNEDCOV::get_id_static),
	StreamListItem(&MavlinkStreamEstimatorStatus::new_instance, &MavlinkStreamEstimatorStatus::get_name_static, &MavlinkStreamEstimatorStatus::get_id_static),
	StreamListItem(&MavlinkStreamAttPosMocap::new_instance, &MavlinkStreamAttPosMocap::get_name_static, &MavlinkStreamAttPosMocap::get_id_static),
	StreamListItem(&MavlinkStreamHomePosition::new_instance, &MavlinkStreamHomePosition::get_name_static, &MavlinkStreamHomePosition::get_id_static),
	StreamListItem(&MavlinkStreamServoOutputRaw<0>::new_instance, &MavlinkStreamServoOutputRaw<0>::get_name_static, &MavlinkStreamServoOutputRaw<0>::get_id_static),
	StreamListItem(&MavlinkStreamServoOutputRaw<1>::new_instance, &MavlinkStreamServoOutputRaw<1>::get_name_static, &MavlinkStreamServoOutputRaw<1>::get_id_static),
	StreamListItem(&MavlinkStreamServoOutputRaw<2>::new_instance, &MavlinkStreamServoOutputRaw<2>::get_name_static, &MavlinkStreamServoOutputRaw<2>::get_id_static),
	StreamListItem(&MavlinkStreamServoOutputRaw<3>::new_instance, &MavlinkStreamServoOutputRaw<3>::get_name_static, &MavlinkStreamServoOutputRaw<3>::get_id_static),
	StreamListItem(&MavlinkStreamHILActuatorControls::new_instance, &MavlinkStreamHILActuatorControls::get_name_static, &MavlinkStreamHILActuatorControls::get_id_static),
	StreamListItem(&MavlinkStreamPositionTargetGlobalInt::new_instance, &MavlinkStreamPositionTargetGlobalInt::get_name_static, &MavlinkStreamPositionTargetGlobalInt::get_id_static),
	StreamListItem(&MavlinkStreamLocalPositionSetpoint::new_instance, &MavlinkStreamLocalPositionSetpoint::get_name_static, &MavlinkStreamLocalPositionSetpoint::get_id_static),
	StreamListItem(&MavlinkStreamAttitudeTarget::new_instance, &MavlinkStreamAttitudeTarget::get_name_static, &MavlinkStreamAttitudeTarget::get_id_static),
	StreamListItem(&MavlinkStreamRCChannels::new_instance, &MavlinkStreamRCChannels::get_name_static, &MavlinkStreamRCChannels::get_id_static),
	StreamListItem(&MavlinkStreamManualControl::new_instance, &MavlinkStreamManualControl::get_name_static, &MavlinkStreamManualControl::get_id_static),
	StreamListItem(&MavlinkStreamTrajectoryRepresentationWaypoints::new_instance, &MavlinkStreamTrajectoryRepresentationWaypoints::get_name_static, &MavlinkStreamTrajectoryRepresentationWaypoints::get_id_static),
	StreamListItem(&MavlinkStreamOpticalFlowRad::new_instance, &MavlinkStreamOpticalFlowRad::get_name_static, &MavlinkStreamOpticalFlowRad::get_id_static),
	StreamListItem(&MavlinkStreamActuatorControlTarget<0>::new_instance, &MavlinkStreamActuatorControlTarget<0>::get_name_static, &MavlinkStreamActuatorControlTarget<0>::get_id_static),
	StreamListItem(&MavlinkStreamActuatorControlTarget<1>::new_instance, &MavlinkStreamActuatorControlTarget<1>::get_name_static, &MavlinkStreamActuatorControlTarget<1>::get_id_static),
	StreamListItem(&MavlinkStreamActuatorControlTarget<2>::new_instance, &MavlinkStreamActuatorControlTarget<2>::get_name_static, &MavlinkStreamActuatorControlTarget<2>::get_id_static),
	StreamListItem(&MavlinkStreamActuatorControlTarget<3>::new_instance, &MavlinkStreamActuatorControlTarget<3>::get_name_static, &MavlinkStreamActuatorControlTarget<3>::get_id_static),
	StreamListItem(&MavlinkStreamNamedValueFloat::new_instance, &MavlinkStreamNamedValueFloat::get_name_static, &MavlinkStreamNamedValueFloat::get_id_static),
	StreamListItem(&MavlinkStreamDebug::new_instance, &MavlinkStreamDebug::get_name_static, &MavlinkStreamDebug::get_id_static),
	StreamListItem(&MavlinkStreamDebugVect::new_instance, &MavlinkStreamDebugVect::get_name_static, &MavlinkStreamDebugVect::get_id_static),
	StreamListItem(&MavlinkStreamNavControllerOutput::new_instance, &MavlinkStreamNavControllerOutput::get_name_static, &MavlinkStreamNavControllerOutput::get_id_static),
	StreamListItem(&MavlinkStreamCameraCapture::new_instance, &MavlinkStreamCameraCapture::get_name_static, &MavlinkStreamCameraCapture::get_id_static),
	StreamListItem(&MavlinkStreamCameraTrigger::new_instance, &MavlinkStreamCameraTrigger::get_name_static, &MavlinkStreamCameraTrigger::get_id_static),
	StreamListItem(&MavlinkStreamCameraImageCaptured::new_instance, &MavlinkStreamCameraImageCaptured::get_name_static, &MavlinkStreamCameraImageCaptured::get_id_static),
	StreamListItem(&MavlinkStreamDistanceSensor::new_instance, &MavlinkStreamDistanceSensor::get_name_static, &MavlinkStreamDistanceSensor::get_id_static),
	StreamListItem(&MavlinkStreamExtendedSysState::new_instance, &MavlinkStreamExtendedSysState::get_name_static, &MavlinkStreamExtendedSysState::get_id_static),
	StreamListItem(&MavlinkStreamAltitude::new_instance, &MavlinkStreamAltitude::get_name_static, &MavlinkStreamAltitude::get_id_static),
	StreamListItem(&MavlinkStreamADSBVehicle::new_instance, &MavlinkStreamADSBVehicle::get_name_static, &MavlinkStreamADSBVehicle::get_id_static),
	StreamListItem(&MavlinkStreamCollision::new_instance, &MavlinkStreamCollision::get_name_static, &MavlinkStreamCollision::get_id_static),
	StreamListItem(&MavlinkStreamWind::new_instance, &MavlinkStreamWind::get_name_static, &MavlinkStreamWind::get_id_static),
	StreamListItem(&MavlinkStreamMountOrientation::new_instance, &MavlinkStreamMountOrientation::get_name_static, &MavlinkStreamMountOrientation::get_id_static),
	StreamListItem(&MavlinkStreamHighLatency2::new_instance, &MavlinkStreamHighLatency2::get_name_static, &MavlinkStreamHighLatency2::get_id_static),
	StreamListItem(&MavlinkStreamGroundTruth::new_instance, &MavlinkStreamGroundTruth::get_name_static, &MavlinkStreamGroundTruth::get_id_static),
	StreamListItem(&MavlinkStreamPing::new_instance, &MavlinkStreamPing::get_name_static, &MavlinkStreamPing::get_id_static)
};

mavlink是怎么定时发送消息的?

  • 添加消息、设置发送周期
    在mavlink_main.cpp加入自定义的消息以及期望的更新频率,比如:
    configure_stream("CA_TRAJECTORY", 100.0f);

其实就是在_streams中查找stream_name,如果找到,则set_interval(新的interval)

  • 数据结构
    _streams是整个类维护的链表,用来记录目前活跃的stream消息。

  • 发送消息
    在mavlink_main.cpp的while循环中,通过下列代码遍历stream并发送:

/* update streams */
// 对_streams列表中的每个stream都更新.
// 这里的更新就包括了send stream message
MavlinkStream *stream;
LL_FOREACH(_streams, stream) {
	stream->update(t);   //t是时间

	if (!_first_heartbeat_sent) {
		if (_mode == MAVLINK_MODE_IRIDIUM) {
			if (stream->get_id() == MAVLINK_MSG_ID_HIGH_LATENCY2) {
				_first_heartbeat_sent = stream->first_message_sent();
			}
		} else {
			if (stream->get_id() == MAVLINK_MSG_ID_HEARTBEAT) {
				_first_heartbeat_sent = stream->first_message_sent();
			}
		}
	}
}

其中update会调用各个message对应的class(比如上面的MavlinkStreamHeartbeat)的send函数。

mavlink是怎么接收消息的?

mavlink_main.cpp的task_main中调用:

MavlinkReceiver::receive_start(&_receive_thread, this);

recieve_start创建了一个thread,在thread中,用MavlinkReceiver::start_helper创建MavlinkReceiver对象,并执行MavlinkReceiver::receive_thread(void *arg),接收数据。

mavlink是怎么解析接收消息的?

在mavlink_receiver.h的class MavlinkReceiver中增加一个用来处理接收信息的函数,类似这样的:

	template<class T>
	void handle_message_command_both(mavlink_message_t *msg, const T &cmd_mavlink,
					 const vehicle_command_s &vehicle_command);
	void handle_message_command_ack(mavlink_message_t *msg);
	void handle_message_optical_flow_rad(mavlink_message_t *msg);
	...

这个消息收到之后要转成uorb,再在内部传递,因此还要在这个类中增加一个uORB消息发布者,类似于:

	orb_advert_t _global_pos_pub;
	orb_advert_t _local_pos_pub;
	orb_advert_t _attitude_pub;
	orb_advert_t _gps_pub;
	...

然后再写一段上面声明的handle函数,该函数包括了对接收的消息进行解码:

void
MavlinkReceiver::handle_message_optical_flow_rad(mavlink_message_t *msg)
{
	/* optical flow */
	mavlink_optical_flow_rad_t flow;
	mavlink_msg_optical_flow_rad_decode(msg, &flow);

	int32_t flow_rot_int;
	param_get(param_find("SENS_FLOW_ROT"), &flow_rot_int);
	const enum Rotation flow_rot = (Rotation)flow_rot_int;

	struct optical_flow_s f = {};

并确定函数在MavlinkReceiver::handle_message()中被调用

	case MAVLINK_MSG_ID_OPTICAL_FLOW_RAD:
		handle_message_optical_flow_rad(msg);
		break;

这个handle_message是被MavlinkReceiver::receive_thread调用的。

本文内容由网友自发贡献,版权归原作者所有,本站不承担相应法律责任。如您发现有涉嫌抄袭侵权的内容,请联系:hwhale#tublm.com(使用前将#替换为@)

PX4中的mavlink 的相关文章

  • 【8-12】树莓派部署t265+px4飞控实现无人机视觉定位

    在之前的文章中 xff0c 我们已经成功在树莓派 xff08 ubuntu mate 18 04 xff09 上部署了T265的追踪摄像头 本文将利用MAVROS协议 xff0c 将T265测量的位姿信息发送给px4固件 xff0c 实现室
  • PX4位置控制offboard模式说明

    offboard模式的开发及应用 一 px4固件的模式 px4固件支持10几种飞行模式 xff0c 从代码结构上分析 xff0c 分为基本模式 自定义模式和自定义子模式 1 基本模式 基本模式又分为 xff0c 位置控制模式 自稳模式 手动
  • 关于PX4中的高度若干问题

    飞行的高度是如何测量的 xff1f 地面的高度和海平面的高度差别很大 xff0c 飞控又是如何有效判别进行降落的 xff1f 这是我脑子里的疑问 搜索的一圈发现很少有人讨论这方面的问题 xff0c 于是本次我就直接看一下源代码 xff0c
  • 基于F4/F7/H7飞控硬件和px4飞控固件的廉价自主无人机系统(1)-飞控

    前言 穿越机F4 F7 H7飞控是一系列采用stm32系列F4xx和F7xx处理器的飞控的统称 xff0c 是目前穿越机爱好者非常喜欢使用的飞控硬件 xff0c 其价格也非常便宜180 xff5e 410 而px4则是一款常见的开源飞控固件
  • PX4代码学习系列博客(5)——在px4中添加自己的模块

    怎么在px4中添加自己的模块 在 px4固件目录结构和代码风格 这一节 xff0c 曾经说过NuttX是一个实时的嵌入式系统 xff0c 上面可以像windows那样运行程序 那既然是应用程序 xff0c 那我们应该也能写一些可以在Nutt
  • PX4 Bootloader下载及编译过程中的问题解决

    买来的雷迅的板子都是Bootloader已经烧进去了 xff0c Fireware也已经刷进去了 如果是自制的板子 xff0c 上位机根本没法识别板子 xff0c 必须先烧写下载Bootloader后编译好的bin文件 这篇记一下自己下载及
  • px4 avoidance笔记

    最近在用px4官方的avoidance代码跑硬件避障 xff0c 官方介绍了只要生成符合sensor msgs PointCloud2点云信息就能使用 xff0c 因此为了应用长基线双目 xff0c 没有使用realsense的相机 xff
  • 无人机仿真—PX4编译,gazebo仿真及简单off board控制模式下无人机起飞

    无人机仿真 PX4编译 xff0c gazebo仿真及简单off board控制模式下无人机起飞 前言 在上篇记录中 xff0c 已经对整体的PX4仿真环境有了一定的了解 xff0c 现如今就要开始对无人机进行起飞等仿真环境工作 xff0c
  • DroneKit教程(五):使用自定义MAVLink指令

    DroneKit教程 xff08 五 xff09 xff1a 使用自定义MAVLink指令 DroneKit的实质是通过发送和接受MAVLink消息 xff0c 向飞控发送控制指令 从飞控获取各种状态信息 DroneKit的所有内置功能都是
  • PX4模块设计之一:SITL & HITL模拟框架

    PX4模块设计之一 xff1a SITL amp HITL模拟框架 1 模拟框架1 1 SITL模拟框架1 2 HITL模拟框架 2 模拟器类型3 MAVLink API4 总结 基于PX4开源软件框架简明简介的框架设计 xff0c 逐步分
  • PX4模块设计之十七:ModuleBase模块

    PX4模块设计之十七 xff1a ModuleBase模块 1 ModuleBase模块介绍2 ModuleBase类介绍3 ModuleBase类功能介绍3 1 模块入口3 2 模块启动3 3 模块停止3 4 状态查询3 5 任务回调3
  • PX4模块设计之三十:Hysteresis类

    PX4模块设计之三十 xff1a Hysteresis类 1 Hysteresis类简介2 Hysteresis类成员变量介绍3 Hysteresis类迟滞逻辑4 Hysteresis类重要方法4 1 Hysteresis bool ini
  • PX4模块设计之三十一:ManualControl模块

    PX4模块设计之三十一 xff1a ManualControl模块 1 ManualControl模块简介2 模块入口函数2 1 主入口manual control main2 2 自定义子命令custom command 3 Manual
  • PX4模块设计之四十三:icm20689模块

    PX4模块设计之四十三 xff1a icm20689模块 1 icm20689模块简介2 模块入口函数2 1 主入口icm20689 main2 2 自定义子命令custom command2 3 模块状态print status 重载 3
  • PX4模块设计之四十五:param模块

    PX4模块设计之四十五 xff1a param模块 1 param模块简介2 模块入口函数param main3 重要函数列表4 总结5 参考资料 1 param模块简介 Description Command to access and
  • PX4模块设计之四十六:dataman模块

    PX4模块设计之四十六 xff1a dataman模块 1 dataman模块简介2 模块入口函数dataman main3 dataman模块重要函数3 1 start3 2 stop3 3 status3 4 task main 4 A
  • PX4飞控之自主返航(RTL)控制逻辑

    本文基于PX4飞控1 5 5版本 xff0c 分析导航模块中自护返航模式的控制逻辑和算法 自主返航模式和导航中的其他模式一样 xff0c 在Navigator main函数中一旦触发case vehicle status s NAVIGAT
  • 【PX4 飞控剖析】06 树莓派加载安装ROS,Mavros以及PX4固件

    PX4 飞控剖析 06 树莓派加载安装Mavros以及PX4固件 1 树莓派 刷镜像1 1 用Win32DiskImager刷入ubuntu mate 16 04 2 desktop armhf raspberry pi的镜像 1 2 开机
  • 大神浅谈无人机飞控软件设计 系统性总结

    写在前面 深感自己对飞控软件 算法的知识点过于杂乱 很久没有进行系统的总结了 因此决定写几篇文章记录一些飞控开发过程的知识点 主要是针对一些软件 算法部分进行讨论 如内容有错误 欢迎指出 1 飞控软件的基本模块 无人机能够飞行主要是依靠传感
  • 飞行姿态解算(三)

    继之前研究了一些飞行姿态理论方面的问题后 又找到了之前很流行的一段外国大神写的代码 来分析分析 第二篇文章的最后 讲到了文章中的算法在实际使用中有重大缺陷 大家都知道 分析算法理论的时候很多情况下我们没有考虑太多外界干扰的情况 原因是很多情

随机推荐

  • [折腾日记]PX4编译环境各种解决方案(ubuntu)

    这篇博客可以解决 PX4编译环境的安装 强烈建议使用Ubuntu16 04的64位版本 xff01 方法1 xff1a 官方脚本 如果你是新装的Ubuntu还没有装软件 那么用官方脚本可以直接安装 官方提供了4个脚本 The scripts
  • ubuntu 12.04英文版设置成中文版

    适用于ubuntu 12 04英文版的系统 xff0c 其它版本的设置应该是大同小异的 进入ubuntu系统 xff0c 在顶部齿状标志找到system 2 在personal找到Language Support 3 进入Language
  • [资料]无人机资料大满足

    资料大汇总 xff0c 论文 xff0c 电子书 xff0c 博客 xff0c 网站看这一篇就够了 精选论文下载 Cubli 方盒机器人为何具有超级平衡能力 xff0c 技术难点是什么 xff1f 苏黎世联邦理工学院 xff08 ETH Z
  • [资料]《现代操作系统》《操作系统概念(操作系统恐龙书)》官方英文电子档

    准备学习一下操作系统 查了很多资料 xff0c 发现大神们统一推荐的两本好书 现代操作系统 Modern Operating Systems Global Edition 4th Edition xff0c 这本书是教材 xff0c Tan
  • [飞控][算法]APM姿态控制—加速度转倾斜角函数和四元数转轴角函数解析(修正)

    https zinghd gitee io blog accel to lean angles to axis angle
  • [飞控]从零开始建模(三)-控制分配浅析

    根据之前的文章 xff0c 我们的模型其实已经完成了 xff0c 模型的输入是四个电机的转速 xff0c 输出是我们需要的状态 位置 xff0c 速度 xff0c 加速度 xff0c 角加速度 xff0c 角速度 xff0c 角度 xff0
  • [飞控]姿态误差(三)-四元数和轴角求误差

    https zinghd gitee io Att err3
  • Matlab中的Smith 预估器

    Smith Predictor是针对时滞系统的 原理 xff1a 看Matlab help中的 34 Control of Processes with Long Dead Time The Smith Predictor 34 足矣 xf
  • meson和pkg-config

    最近再看simple cam xff0c 它是用meson构建的 有这样一句 xff1a deps 61 dependency 39 libevent pthreads 39 执行编译时报错 xff1a meson build 16 0 E
  • ubuntu 22.04右上角找不到wifi图标,有线网络也失效

    起因是我将显示驱动由默认的nouveau换成了nvidia xff0c 然后重启后在右上角就看不到wifi图标了 执行 96 sudo lshw c network 96 显示 xff1a network UNCLAIMED 执行sudo
  • PIE

    1 以2812为例 xff08 28335也是 xff09 xff0c PIE Vector在Memory Map的位置是0x0D00 0x0E00 这个是在cmd文件中的MEMORY部分指定的 xff1a PIE VECT origin
  • VS2013取消预编译头

    创建C 43 43 Win32控制台时忘了取消预编译头 xff0c 怎么取消 xff1f 右键项目 gt 属性 gt 配置属性 gt C C 43 43 gt 预编译头 gt 不使用预编译头 改天再写预编译头是干嘛的
  • Xmanager 6 图形化界面连接Centos7 配置步骤

    1 前提 Centos 7已经安装就绪 2 安装Xmanager 6 本博客以Xmanager6 0 0108为例 a 首先双击可执行文件 出现如下安装界面 点击 下一步 nbsp nbsp nbsp nbsp nbsp nbsp nbsp
  • VS中VC++目录中的$是什么意思

    VC ExecutablePath x64 项目是x64平台 WindowsSDK ExecutablePath VS ExecutablePath MSBuild ExecutablePath VC IncludePath VCInsta
  • 关于单应性矩阵的理解:Homography matrix for dummies

    尽量写的通俗一点 xff0c 因为从某种程度上讲 xff0c 本人也是dummy 1 先说homogeneous coordinate xff0c 齐次坐标 一幅2D图像上的非齐次坐标为 x y xff0c 而齐次坐标为 x y 1 xff
  • 关于RANSAC的理解

    先说最小二乘 ok xff0c 你手头有一堆数据 xff0c 比如这些蓝点 xff1a 那么我们假设它符合一个直线模型 xff1a y 61 ax 43 b xff0c 用最小二乘就可以很容易求解出未知参数a和b 最小二乘大法确实好哇 xf
  • Visual Studio中监视数组

    比如有一个double h 9 xff0c 如果选择监视 xff0c 那么就只会监视h 0 xff0c 如果想监视其他元素 xff0c 难道只能h 1 h 2 一个个的添加吗 xff1f 当然不需要 xff0c 在监视中输入h 9就可以了
  • 在编译PX4之前,你需要知道的几件事

    1 在git上clone代码 xff0c 必须是clone xff0c 因为编译时需要有 git文件夹 如果你看Makefile就会发现有这么一行 xff1a Enforce the presence of the GIT reposito
  • 马氏距离与卡方分布

    最近在看 Fundamentals of object tracking xff0c 看到最近邻滤波时 xff0c 碰到了题中的两个概念 以下内容基本来自wiki xff0c 读者有不懂的地方看wiki更清晰明了 1 马氏距离 Mahala
  • PX4中的mavlink

    简介 px4与地面站的通信协议是mavlink xff0c 对于其消息格式的介绍看这里和这里 需要注意几点 xff1a 不光是px4与qgroundcontrol通信通过mavlink xff0c 有一些sensor也支持mavlink m