PX4的控制与输出

2023-05-16

文章目录

  • 前言
    • 控制器部分
    • 输出部分
      • 控制组
      • 混控器
      • 混控器的启动
      • 信号输出


前言


这篇记录一下自己分析PX4从位置控制->速度控制->姿态控制->角速度控制->电机输出的源码框架的阅读与理解,便于之后自己修改控制器。在这个部分前面的navigatorcommander模块不在本次谈论范围之内。


控制器部分


首先说明一下,在PX4的代码中,无人机的位置控制和速度控制的代码并不是分开的而是都在mc_pos_control里,毕竟位置控制就是一个P控制,速度控制也就是一个常规的PID控制,确实也没啥好写的。

首先对于阅读过ardupilot的控制框架的我来说,PX4的源代码无疑清爽了很多,不同的应用模块之间使用urob进行通讯,使得他们之间不再有相互耦合。所以大部分情况,我们只需要在.h文件中找到订阅和发布的话题,就可以用它们方便的找到上下相互配合的应用模块。一开始,我发现有些模块里:比如mc_pos_control里发布了vehicle_attitude_setpoint话题,而mc_att_control里也发布了vehicle_attitude_setpoint话题,理所应当,它也订阅了这个话题。当时我就一下整不会了?别的模块发,然后它自己也发?那他订阅的时候是用的那一个,而且为啥会自己给自己发呢?带着疑惑,我继续往下读,然后直到看到下面几行代码,我明白了。

// Generate the attitude setpoint from stick inputs if we are in Manual/Stabilized mode
if (_v_control_mode.flag_control_manual_enabled &&
	 !_v_control_mode.flag_control_altitude_enabled &&
	 !_v_control_mode.flag_control_velocity_enabled &&
	 !_v_control_mode.flag_control_position_enabled) {

		 generate_attitude_setpoint(q, dt, _reset_yaw_sp);
		 attitude_setpoint_generated = true;

		} else {
				_man_x_input_filter.reset(0.f);
				_man_y_input_filter.reset(0.f);
		}

是的,这里mc_att_control想要发布vehicle_attitude_setpoint是有条件的,需要进行一个判断我们现在是处于手动模式下(PX4 四旋翼机型的manual和stabilized模式是完全一样的,只有固定翼下二者才有区别),也就是说mc_pos_control此时是不工作的,这个时候mc_att_control才会自己根据我们的摇杆输入来来生成姿态控制指令并发布然后自己又订阅来进行下一步处理,mc_rate_control也是相似的。

说完这些我们先看看姿态控制和角速度控制部分,因为这两个部分的代码条理都非常清晰,姿态控制mc_att_control采用四元数控制生成姿态角速度的控制指令并发布相应的vehicle_rates_setpoint话题,角速度控制mc_rate_control常规的PID控制来生成力矩的控制指令并发布相应的话题actuator_controls_0。以上控制的具体框架和说明,到PX4官方开发者手册查看即可,写的很清楚明白,这里就不再赘述。


输出部分


控制组

到这里就数据已经发布到了控制组0中,我们可以在PX4中找到控制组0的具体定义。对于四旋翼的控制而言,我们基本只用看控制组0即可,其他的控制组可以先不管。

Control Group #0 (Flight Control)0: roll (-1..1)1: pitch (-1..1)2: yaw (-1..1)3: throttle (0..1 normal range, -1..1 for variable pitch / thrust reversers)4: flaps (-1..1)5: spoilers (-1..1)6: airbrakes (-1..1)7: landing gear (-1..1)

从以上定义我们可以看到,控制器最终的输出被映射到(-1,1)区间中,那么接下来我们就需要将利用这些控制信号以及mixer混控器来产生最终的实际信号输出。

混控器

混控器说简单它可以很简单,说复杂也可以很复杂。本质上来说,它的核心作用就是把控制器输出的yaw,pitch,roll,thrust等控制量根据实际输出的执行器产生的作用矩阵将其进行实际的输出分配。所以它的本质不过就是一个变换矩阵而已。PX4中一共有4种混控器类型:R,H,M,Z。他们分别代表了多旋翼混控器,直升机构型混控器,简单加法混控器,空混控器。我们可以看看脚本语法:

M: <control count>
O: <-ve scale> <+ve scale> <offset> <lower limit> <upper limit> <traversal time>
S: <group> <index> <-ve scale> <+ve scale> <offset> <lower limit> <upper limit>
  • 脚本中只有以 大写字母 + 的组合的开头的一行才会生效,别的默认都是注释。

  • M:后紧跟的数字表示是该通道由多少个输入源混合而成

  • O: 表示输出的一个幅值约束,最后是一个移动时间可选项,比如我们用舵机控制一个起落架,那么显然可以把整个值设置大一些。这一项如果不写的话,则默认为:
    O: 10000 10000 0 -10000 10000

  • S: 表示是输出的信号来源 <控制组别号> <控制量索引号>后面也是一些限幅约束


R: <geometry> <roll scale> <pitch scale> <yaw scale> <idlespeed>

支持的几何构型<geometry> 包括:

  • 4x : quadrotor in X configuration
  • 4+ : quadrotor in + configuration
  • 6x : hexacopter in X configuration
  • 6+ : hexacopter in + configuration
  • 8x : octocopter in X configuration
  • 8+ : octocopter in + configuration
Z:

空mixer用来占位,表示该通道什么也不输出。脚本中写每一个混空按照顺序依次映射到实际的1,2,3,4…通道上

H: <number of swash-plate servos, either 3 or 4>
T: <throttle setting at thrust: 0%> <25%> <50%> <75%> <100%>
P: <collective pitch at thrust: 0%> <25%> <50%> <75%> <100%>
S: <angle> <arm length> <scale> <offset> <lower limit> <upper limit>

整个由于目前我不用所以就先不写了。

这里简单有兴趣继续深究的,可以去看官网,要是官网看不明白可以去看阿木实验室的混控器课程或者大佬文章1以及大佬文章2


混控器的启动

混控器的启动是在启动脚本rcS的运行下一步步加载的。大概的加载顺序是rcS->rc.autostart->4001_quad_x->rc.mc_defaults
4001_quad_x中设置了set MIXER quad_x 其中quad_x 就对应了脚本quad_x.main.mix,其内容如下:

R: 4x
M: 1
S: 3 5 10000 10000 0 -10000 10000
M: 1
S: 3 6 10000 10000 0 -10000 10000
Z:
Z:

rc.mc_defaults设置了set MIXER_AUX pass 其中pass对应了脚本pass.aux.mix,其内容如下:

M: 1
S: 3 5 10000 10000 0 -10000 10000
M: 1
S: 3 6 10000 10000 0 -10000 10000
M: 1
S: 3 7 10000 10000 0 -10000 10000
M: 1
S: 3 4 10000 10000 0 -10000 10000

多旋翼和固定翼默认装载 pass.aux.mix (如下所示)将遥控器映射到辅助通道输出。

pass.aux.mix的注释如下:

# Manual pass through mixer for servo outputs 1-4

# AUX1 channel (select RC channel with RC_MAP_AUX1 param)
M: 1
S: 3 5  10000  10000      0 -10000  10000

# AUX2 channel (select RC channel with RC_MAP_AUX2 param)
M: 1
S: 3 6  10000  10000      0 -10000  10000

# AUX3 channel (select RC channel with RC_MAP_AUX3 param)
M: 1
S: 3 7  10000  10000      0 -10000  10000

# FLAPS channel (select RC channel with RC_MAP_FLAPS param)
M: 1
S: 3 4  10000  10000      0 -10000  10000

完成上述设置后,之后rcS会执行/etc/init.d/rc.interface 脚本。在该脚本中,将根据之前的设置参数正式加载quad_x.main.mixpass.aux.mix两个脚本,至此混控器就完成启动了


信号输出

在信号输出的最后阶段我们就有两种情况,一种情况是飞控用协处理器px4io输出最终控制信号,一种情况是飞控FMU直接输出最终控制信号。第一种情况,有大佬文章说的很清楚,阿木实验室的混控器课程也讲的非常清楚,这里我不再赘述。

这里我想主要记录一下第二种情况,这种情况也是目前大家做四旋翼无人用的最多的情况。电机控制信号直接由FMU输出,信号的速率不仅更快一些,而且开发也更简洁一点。

这里我们主要说PWM的输出的,DSHOT的输出显然同理,不再赘述。
这里主要涉及到了到src/drivers/pwm_outsrc/lib/mixersrc/lib/mixer_module这三个文件(更底层的一些系统操作我们就先不关注了)。

首先需要说明的是在lib里的程序都不会属于应用程序,所以说这么一说,大家自然就很清楚了,必然是pwm_out的程序是作为进程执行,而mixermixer_module中的类和函数之类的则在pwm_out中被定义被调用。

src/lib/mixer文件中有各种mixer的定义和程序实现,有兴趣的朋友请移步这篇文章(这篇文章对混控器代码和混控脚本都作了详细说明)。建议大家阅读,PX4中混控器不仅通过效率矩阵将控制力和控制力矩分配到各个电机,而且还包含了输出抗饱和以及旋翼动力与PWM的映射关系,这些都会直接影响到最后的控制效果,而不是说我们只关注前面控制器设计就可以了。当然了,就目前来说,它的效果是够用的,我们改控制器时可以不用关心这里,但是如果说我们要设计一个对旋翼模型进行参数辨识的较为准确的拉力模型后,这个地方也需要我们自己改一改了。

src/lib/mixer_module基本上可以说是为上层应用调用mixer做好各种方便的函数接口,尤其是里面MixingOutput的构造。之前我们说到过,最终的电机输出的信号取决于actuator_controls_0的控制指令和mixer混控器两个东西。那么在下面的构造函数中我们可以看到,这里显然对actuator_controls_0的话题进行订阅的操作。这个构造具体的实现我没太明白,不过可以明确的是这个类的成员中一定拥有了actuator_controls_0的数据。

MixingOutput::MixingOutput(uint8_t max_num_outputs, OutputModuleInterface &interface,
			   SchedulingPolicy scheduling_policy,
			   bool support_esc_calibration, bool ramp_up)
	: ModuleParams(&interface),
	  _control_subs{
	{&interface, ORB_ID(actuator_controls_0)},
	{&interface, ORB_ID(actuator_controls_1)},
	{&interface, ORB_ID(actuator_controls_2)},
	{&interface, ORB_ID(actuator_controls_3)},
	{&interface, ORB_ID(actuator_controls_4)},
	{&interface, ORB_ID(actuator_controls_5)},
}, // 部分构造函数

接下来要说明的src/lib/mixer_module中的update函数,这个函数非常重要,它完成了许多重要的工作。这里我贴出部分重要代码,大家再看这些关键注释就可以很清楚了。


/* get controls for required topics */
if (_control_subs[i].copy(&_controls[i])) //这里就复制了控制组信号到_controls
/* do mixing */
const unsigned mixed_num_outputs = _mixers->mix(outputs, _max_num_outputs);
/* the output limit call takes care of out of band errors, NaN and constrains */
output_limit_calc(_throttle_armed, armNoThrottle(), mixed_num_outputs, _reverse_output_mask,_disarmed_value, _min_value, _max_value, outputs, _current_output_value, &_output_limit);
/* now return the outputs to the driver */
if (_interface.updateOutputs(stop_motors, _current_output_value, mixed_num_outputs, n_updates)) {
		actuator_outputs_s actuator_outputs{};
		setAndPublishActuatorOutputs(mixed_num_outputs, actuator_outputs);

		publishMixerStatus(actuator_outputs);
		updateLatencyPerfCounter(actuator_outputs);
	}

  • 获得控制量
  • 进行混控
  • 进行输出限制幅处理
  • 将输出返回到驱动(这里的驱动当然就是pwm,dshot驱动之类的了)

我们可以看到这里是通过下面这个函数更新了输出的电机控制信号值

_interface.updateOutputs(stop_motors, _current_output_value, mixed_num_outputs, n_updates)

这个函数在最初的 OutputModuleInterface类中是一个虚函数,它将在 OutputModuleInterface的派生类PWMout中被重新定义,也就赋予了它实际的输出功能,如下所示。当然作为一个输出接口,它也可以同样被dshot重定义从而输出dshot信号。

bool PWMOut::updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS],
			   unsigned num_outputs, unsigned num_control_groups_updated)
{
	if (_test_mode) {
		return false;
	}

	/* output to the servos */
	if (_pwm_initialized) {
		for (size_t i = 0; i < math::min(_num_outputs, num_outputs); i++) {
			up_pwm_servo_set(_output_base + i, outputs[i]);
		}
	}

	/* Trigger all timer's channels in Oneshot mode to fire
	 * the oneshots with updated values.
	 */
	if (num_control_groups_updated > 0) {
		up_pwm_update(); // TODO: review for multi
	}

	return true;
}

就在这里,调用了来自于操作系统中的up_pwm_servo_set(unsigned channel, servo_position_t value)函数,该函数再进一步调用底层函数int io_timer_set_ccr(unsigned channel, uint16_t value)将对应的pwm输出写入对应通道的CCR寄存器中,玩过stm32的朋友应该很清楚这个寄存器就是产生pwm的寄存器。

上述说描述的src/lib/mixer_module的重要函数,最终在src/drivers/pwm_out中的Run函数中一次调用中完成:

_mixing_output.update();

至此PX4整个控制和输出的过程的分析说明便画上句号。

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

PX4的控制与输出 的相关文章

  • ardupilot & px4 书写自己的app & drivers (二)

    新建任务列表任务 打印时间 任务列表 const AP Scheduler span class hljs tag Task span Copter span class hljs tag scheduler tasks span span
  • 下载并构建PX4

    根据官方的文档 xff0c PX4下载和构建的方式有两种 xff1a Linux系列的Console模式 xff08 当然也支持Windows下的MINGW32 xff09 和Windows模式 在Windows平台下 xff0c 我们习惯
  • PX4通过I2C方式添加自定义传感器(3)

    添加自定义传感器并实现数据的发送和订阅 1 前期准备 1 1 建立文件夹和相关文件配置 我是在src drivers distance sensor文件夹下操作的 xff0c 当然其他文件夹下都类似 首先建立了两个文件夹angle sour
  • 编译PX4固件

    PX4编译 文章目录 PX4编译疑难杂症bug1bug2catkin build isolated 官方脚本Step1Step2 安装常用依赖Step3 创建并运行脚本Step4 补全代码子模块Step5 验证仿真 官方offboard 例
  • 【2020-8-9】APM,PX4,GAZEBO,MAVLINK,MAVROS,ROS之间的关系以及科研设备选型

    0 概述 无人机自主飞行平台可以分为四个部分 xff1a 动力平台 xff0c 飞行控制器 xff0c 机载电脑和模拟平台 动力平台 xff1a 负责执行飞行任务 xff0c 包括螺旋桨 电机 机架等 xff0c 用于科研的一般都是F380
  • 【8-12】树莓派部署t265+px4飞控实现无人机视觉定位

    在之前的文章中 xff0c 我们已经成功在树莓派 xff08 ubuntu mate 18 04 xff09 上部署了T265的追踪摄像头 本文将利用MAVROS协议 xff0c 将T265测量的位姿信息发送给px4固件 xff0c 实现室
  • 飞行机器人(七)仿真平台XTDrone + PX4编译

    0 编译PX4固件 参考仿真平台基础配置教程 xff08 中文详细教程 xff09 仿真平台基础配置 语雀 yuque com https www yuque com xtdrone manual cn basic config 按照教程
  • Ubuntu20.04+MAVROS+PX4+Gazebo保姆级安装教程

    Ubuntu20 04 43 MAVROS 43 PX4 43 Gazebo 安装PX4步骤安装MAVROS安装QGCPX4仿真 安装PX4步骤 从github上clone源码 span class token function git s
  • px4源码编译指南

    px4源码编译指南 强烈推荐大家去看官网的英文文档 xff0c 国内的博客杂七杂八 xff0c 官网的中文也很久没有更新 xff0c 这几天自己踩了很多坑 xff0c 写个教程希望能帮助到大家 xff08 本文选用平台是pixhawk1 1
  • PX4进入系统控制台以及运行程序

    这里提供进入控制台两种办法 1 运行 Tools mavlink shell py dev ttyACM0 是我进入Px4系统控制台的命令 xff0c 进入之后应该是这样 Pixhawk src Firmware Tools mavlink
  • PX4模块设计之六:PX4-Fast RTPS(DDS)简介

    64 TOC PX4模块设计之六 xff1a PX4 Fast RTPS DDS 简介 基于PX4开源软件框架简明简介的框架设计 xff0c 逐步分析内部模块功能设计 PX4 Fast RTPS DDS 具有实时发布 订阅uORB消息接口
  • PX4模块设计之十一:Built-In框架

    PX4模块设计之十一 xff1a Built In框架 1 Nuttx Built In框架2 PX4 Built In框架2 1 NSH Built In关联文件2 2 NSH Built In关联文件生成2 3 NSH Built In
  • PX4模块设计之十三:WorkQueue设计

    PX4模块设计之十三 xff1a WorkQueue设计 1 WorkQueue启动2 WorkQueue接口2 1 基本接口2 2 辅助接口2 3 WorkQueue任务函数2 3 1 Flat Build2 3 2 Protected
  • PX4模块设计之三十三:Sensors模块

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

    PX4模块设计之三十九 xff1a Commander模块 1 Commander模块简介2 模块入口函数2 1 主入口commander main2 2 自定义子命令custom command 3 Commander模块重要函数3 1
  • px4_simple_example和uorb机制

    px4 simple app PX4 Autopilot src exampes px4 simple app xff0c 这个程序是用c语言调用orb API和poll机制订阅和发布通讯数据 xff0c 但是这个例子并不是既有接收又有发送
  • px4无人机常识介绍(固件,px4等)

    专业名词解释 aircraft 任何可以飞或者可以携带物品还是搭载旅客的飞行器统称为飞机 航空器 uav 无人驾驶飞机 vehicle 飞行器 airplane plane aero plane 有机翼和一个或多个引擎的飞行器统称为飞机 D
  • PX4软件在环仿真注意点

    注 xff1a 最新内容参考PX4 user guide 点击此处 PX4下载指定版本代码和刷固件的三种方式 点击此处 PX4sitl固件编译方法 点击此处 PX4开发指南 点击此处 PX4无人机仿真 Gazebo 点击此处 px4仿真 知
  • PX4之常用函数解读

    PX4Firmware 经常有人将Pixhawk PX4 APM还有ArduPilot弄混 这里首先还是简要说明一下 xff1a Pixhawk是飞控硬件平台 xff0c PX4和ArduPilot都是开源的可以烧写到Pixhawk飞控中的
  • PX4:Policy “CMP0097“ is not known to this version of CMake.

    make px4 fmu v3 时报的错 CMake版本的问题 由https blog csdn net zhizhengguan article details 118380965推测 xff0c 删除cmake policy也没事 ma

随机推荐

  • Ubuntu16.04系统中创建新用户

    Ubuntu16 04系统中创建新用户 本文基于Linux的Ubuntu系统新建一个普通用户 xff0c linux系统的用户名为peng 主机名为ubuntu 1 新建用户2 允许该用户以管理员身份执行指令 1 新建用户 1 1 新建只能
  • 如何将dockerhub与github关联

    本文目录 如何将dockerhub账户与github相关联如何在dockerhub中利用github上的Dockfile进行auto build dockerhub具有Create Automated Build xff0c 也就是说 xf
  • UML中的关系

    UML中的关系 UML中的关系 xff08 Relationships xff09 主要包括5种 xff1a 关联关系 聚合关系 依赖关系 泛化关系和实现关系 关联 xff08 Association xff09 关系 关联关系是一种结构化
  • [授权发表]基于 VNCServer + noVNC 构建 Docker 桌面系统

    by Falcon of TinyLab org 2015 05 02 最初发表 xff1a 泰晓科技 聚焦嵌入式 Linux xff0c 追本溯源 xff0c 见微知著 xff01 原文链接 xff1a 基于 VNCServer 43 n
  • Debian 源(source.list)

    在debian下 xff0c 用apt方式安装软件除了可以以网络上的资源为源之外 xff0c 还可以使用本地的资源 下面我就以安装GCC的过程为例 xff0c 说一下整个过程 平台 xff1a debian 4 0 图形界面 资源 xff1
  • boa 编译步骤&&常见错误

    第一步 xff1a 源码包 xff1a boa 0 94 13 tar gz 解压 tar xvf 第二步 xff1a 你会看到10个文件 xff0c 其中有一个是src xff0c 直接进入 src文件目录下 第三步 xff1a 配置 x
  • 推荐几款SSH工具

    SSH 是建立在应用层基础上的安全协议 xff0c 专为远程登录会话和其他网络服务提供安全性的协议 利用 SSH 协议可以有效防止远程管理过程中的信息泄露问题 SSH最初是UNIX系统上的一个程序 xff0c 后来又迅速扩展到其他操作平台
  • WinForm应用实战开发指南 - 如何设计展示应用程序主界面

    WinForm应用程序的开发 xff0c 主窗口的界面设计一般都要求做的更好一些 xff0c 可以根据不同的系统功能模块进行归类整合 xff0c 能使客户迅速寻找到相关功能的同时 xff0c 也能感觉到整体性的美观大方 xff0c 因此主窗
  • PX4+光流模块MTF01的一点使用心得

    1 不知道怎么样把这个给接到飞控的串口4上 应该是因为没找到地方设置串口4的波特率啥的 xff0c 最后还是接到了TELEM2接口上 xff0c 又设置了一下波特率才好用 2 定高效果很好 xff0c 定位效果也还行 3 在出现位置模式下y
  • [论文] Feature Squeezing:Detecting Adversarial Examples in Deep Neural Networks

    思路 xff1a 对抗样本经过feature squeeze处理后大部分增加的干扰会被消除或者减小 xff0c 致使feature squeeze前后的分类结果向量 xff08 distributed vector xff09 L1距离很大
  • 手把手教用matlab做无人驾驶(三)-路径规划A*算法

    这里 xff0c 我们更新主程序如下 xff1a editor Robert Cao 2018 9 1 clc clear all close all disp 39 A Star Path Planing start 39 p start
  • eve-ng导入华为路由器镜像

    iol位置 opt unetlab addons iol bin qemu位置 xff1a opt unetlab addons qemu 设备图标位置 opt unetlab html images icons 设备脚本位置 opt un
  • ROS入门保姆级教程:7-ROS话题通信实现2:自定义消息类型(msg)

    ROS入门往期 xff1a ROS入门保姆级教程 xff1a 1 hello world初体验 ROS入门保姆级教程 xff1a 2 VScode中使用ROS ROS入门保姆级教程 xff1a 3 ROS文件系统 ROS入门保姆级教程 xf
  • 设计模式---订阅发布模式(Subscribe/Publish)

    订阅发布模式定义了一种一对多的依赖关系 xff0c 让多个订阅者对象同时监听某一个主题对象 这个主题对象在自身状态变化时 xff0c 会通知所有订阅者对象 xff0c 使它们能够自动更新自己的状态 将一个系统分割成一系列相互协作的类有一个很
  • 能ping通虚拟机,但ssh连接不上,访问虚拟机服务也不行NAT

    自己的windows ip 跟虚拟机的ip一样 xff0c 产生错觉 xff0c 其实ping的是自己的window主机 xff0c 修改windows 地址后就可以了
  • html5是什么?五大浏览器、网页基本骨架结构与含义、常用标签——学习HTML5第一天的心得总结,若有错误望指正,我将持续更新与大家共同进步。

    注意 xff1a 上方P标签所说的块元素不可嵌套块元素是指在p元素中不建议嵌套块元素 xff0c 如不建议 lt P gt lt div gt lt div gt lt P gt 这种嵌套 xff0c 其他块元素则根据需求嵌套即可 1 ht
  • 新手入门 - 详解 frp 内网穿透 frpc.ini 配置

    本文为 Stille 原创文章 经实践 测试 整理发布 如需转载请联系作者获得授权 并注明转载地址 转载地址 xff1a 新手入门 详解 frp 内网穿透 frpc ini 配置 思有云 IOIOX 前言 本站关于 frp 内网穿透的相关教
  • pixhawk硬件设计粗略解析

    文章目录 前言一 pixhawk是什么 xff1f 二 pixhawk硬件解析总结 前言 本片是个人对NFCYv5飞控的硬件设计的个人分析与笔记 为什么要这么做呢 xff1f 原因很简单 xff0c 一是对pixhawk硬件组成有更加深入的
  • Android IPC机制

    本文首发于个人博客 胖蔡叨叨叨 xff0c 更多相关信息可点击查看 Android IPC机制 IPC IPC Inter Process Communication 进程间通信 xff0c 是指系统中运行的不同进程间的信息交互过程 And
  • PX4的控制与输出

    文章目录 前言控制器部分输出部分控制组混控器混控器的启动信号输出 前言 这篇记录一下自己分析PX4从位置控制 gt 速度控制 gt 姿态控制 gt 角速度控制 gt 电机输出的源码框架的阅读与理解 xff0c 便于之后自己修改控制器 在这个