4、arducopter.cpp
分析ardupilot这套代码首先就是拿arducopter.cpp开刀,
Loop函数的设计框架既要准确,又要高效。总体设计是这样的:
其一用一个计时器定时触发测量;其二所有测量过程都靠中断推进;其三在main函数里不断检查测量是否完成,完成就进行解算。测量过程还是比较耗时间的,基于这样的设计,测量和解算可以同时进行,不会浪费CPU时间在(等待)测量上。而通过计时器触发测量,最大限度保证积分间隔的准确。
整个控制过程主要就集中在arducopter.cpp里面,首先就是scheduler_tasks[]中是需要创建的task线程,如下图中,接收机的rc_loop、arm_motors_check等,还记得上篇博文中介绍的解锁和上锁的操作么,就是在arm_motors_check函数中实现的,以固定的频率去采集遥控器信号。

1)setup函数
然后就是setup函数,在该函数中做的事情还是比较全面的,其中内部调用了一个比较重要的函数init_ardupilot(),该函数做了一系列的初始化,该初始化和上一篇博文介绍的不一样,上一篇主要是配置底层硬件的(如STM32、sensors),而此处的主要是飞行前的检测比那个初始化的晚;比如检测是否有USB连接、初始化UART、打印固件版本、初始化电源检测、初始化RSSI、注册mavlink服务、初始化log、初始化rc_in/out(内部含有电调校准)、初始化姿态/位置控制器、初始化飞行模式、初始化aux_switch、使能失控保护、配置dataflash最后打印“Ready to FLY ”。接下来就几个比较重要的函数(上述标红)进行深入分析。
void Copter::init_rc_in()
{
//rc_map 结合AC_RCMapper.h
channel_roll = RC_Channel::rc_channel(rcmap.roll()-1);
channel_pitch = RC_Channel::rc_channel(rcmap.pitch()-1);
channel_throttle = RC_Channel::rc_channel(rcmap.throttle()-1);
channel_yaw = RC_Channel::rc_channel(rcmap.yaw()-1);
// set rc channel ranges
channel_roll-》set_angle(ROLL_PITCH_INPUT_MAX);//4500
channel_pitch-》set_angle(ROLL_PITCH_INPUT_MAX);
channel_yaw-》set_angle(4500);
channel_throttle-》set_range(g.throttle_min, THR_MAX);//1000
channel_roll-》set_type(RC_CHANNEL_TYPE_ANGLE_RAW);
channel_pitch-》set_type(RC_CHANNEL_TYPE_ANGLE_RAW);
channel_yaw-》set_type(RC_CHANNEL_TYPE_ANGLE_RAW);
//set auxiliary servo ranges
g.rc_5.set_range_in(0,1000);
g.rc_6.set_range_in(0,1000);
g.rc_7.set_range_in(0,1000);
g.rc_8.set_range_in(0,1000);
// set default dead zones
default_dead_zones();
// initialise throttle_zero flag
ap.throttle_zero = true;//注意这个,rc_map好以后把油门配置为0
// true if the throttle stick is at zero, debounced, determines if pilot intends shut-down when not using motor interlock
}
// init_rc_out -- initialise motors and check if pilot wants to perform ESC calibration
void Copter::init_rc_out()
{
motors.set_update_rate(g.rc_speed);
motors.set_frame_orientation(g.frame_orientation);//配置机体类型(+/x)
motors.Init(); // motor initialisation
#if FRAME_CONFIG != HELI_FRAME
motors.set_throttle_range(g.throttle_min, channel_throttle-》radio_min, channel_throttle-》radio_max);//配置油门最大值和最小值 motors.set_hover_throttle(g.throttle_mid);
#endif
for(uint8_t i = 0; i 《 5; i++) {
delay(20);
read_radio();
}
// we want the input to be scaled correctly
channel_throttle-》set_range_out(0,1000);
// check if we should enter esc calibration mode
esc_calibration_startup_check();//电调校准,进入以后首先判断是否有pre-arm,如果没有则直接退出校准。校准过飞机的都知道这个
// enable output to motors
pre_arm_rc_checks();
if (ap.pre_arm_rc_check) {
enable_motor_output();//内部会调用motors.output_min()函数sends minimum values out to the motors,待会介绍该函数
}
// refresh auxiliary channel to function map
RC_Channel_aux::update_aux_servo_function();
// setup correct scaling for ESCs like the UAVCAN PX4ESC which
// take a proportion of speed.
hal.rcout-》set_esc_scaling(channel_throttle-》radio_min, channel_throttle-》radio_max);
}
简单介绍如何如何控制电机转动以及cork() and push(),并在此基础上测试了关于scheduler_tasks[] 中的任务的执行频率是否可以达到要求。测试方法:在scheduler_tasks[] 任务列表的throttle_task中添加一个累加标志位counterflag,每执行一次throttle_task任务就对齐加1,加到100时使电机转动,测试结果约为5S时电机转动,理论是50HZ的周期(不加执行时间是需要2S转动)再加上每次需要的执行时间以后还是比较理想的。
// output_min - sends minimum values out to the motors
void AP_MotorsMatrix::output_min()
{
int8_t i;
// set limits flags
limit.roll_pitch = true;
limit.yaw = true;
limit.throttle_lower = true;
limit.throttle_upper = false;
// fill the motor_out[] array for HIL use and send minimum value to each motor
hal.rcout-》cork();
/*Delay subsequent calls to write() going to the underlying hardware in
order to group related writes together. When all the needed writes are
done, call push() to commit the changes.
This method is optional: if the subclass doesn‘t implement it all calls
to write() are synchronous.*/
for( i=0; i《AP_MOTORS_MAX_NUM_MOTORS; i++ ) {
// AP_MOTORS_MAX_NUM_MOTORS=8
if( motor_enabled[i] ) {
rc_write(i, _throttle_radio_min);
//下面会解析rc_write(uint8_t chan, uint16_t pwm)
}
}
hal.rcout-》push();
/*Push pending changes to the underlying hardware. All changes between a call to cork() and push() are pushed together in a single transaction.This method is optional: if the subclass doesn’t implement it all calls to write() are synchronous.*/
}
//由上述可知在通过HAL层配置数据时使用cork() and push()函数包装需要单次传输的数据。该方法就是为了实现对四个电机同时配置,避免由for语句产生的延时,也是强调同步(synchronous)。
如下解析rc_write(uint8_t chan, uint16_t pwm)
void AP_Motors::rc_write(uint8_t chan, uint16_t pwm)
{
if (_motor_map_mask & (1U《《chan)) {
// we have a mapped motor number for this channel
chan = _motor_map[chan];// mapping to output channels
}
hal.rcout-》write(chan, pwm);//通过HAL层直接输出配置电调
}
Setup()函数的最后一句是fast_loopTimer = AP_HAL::micros(),获取micros()通过层层封装最终就是上篇博文中介绍的hrt,该时间会在下面的loop函数中使用。
2)loop函数
该函数比较重要,fast_loop和schedule_task都是封装在该函数中的,下面主要讲述fast_loop。
// Main loop - 400hz
void Copter::fast_loop()
{
// IMU DCM Algorithm 里面有个update函数,这个函数就是读取解算好的角度信息
read_AHRS();
// run low level rate controllers that only require IMU data
attitude_control.rate_controller_run();
// send outputs to the motors library
motors_output();
// Inertial Nav
read_inertia();
// check if ekf has reset target heading
check_ekf_yaw_reset();
// run the attitude controllers
update_flight_mode();
// update home from EKF if necessary
update_home_from_EKF();
// check if we‘ve landed or crashed
update_land_and_crash_detectors();
// log sensor health
if (should_log(MASK_LOG_ANY)) {
Log_Sensor_Health();
}
}
read_AHRS()内部使用ahrs.update更新AHRS数据。
// run a full DCM update round
Void AP_AHRS_DCM::update(void)
{
// tell the IMU to grab some data
_ins.update();//update gyro and accel values from backends具体实现过程详见源码
// ask the IMU how much time this sensor reading represents
delta_t = _ins.get_delta_time();
// Integrate the DCM matrix using gyro inputs
//使用陀螺仪数据更新DCM矩阵(方向余弦矩阵:direction-cosine-matrix ),使用刚刚测量出来的陀螺仪值、以及上个周期对陀螺仪的补偿值进行角度更新
matrix_update(delta_t);
// Normalize the DCM matrix 归一化处理
normalize();
// Perform drift correction
drift_correction(delta_t);
// paranoid check for bad values in the DCM matrix
check_matrix();
// Calculate pitch, roll, yaw for stabilization and navigation
euler_angles();
// update trig values including _cos_roll, cos_pitch
update_trig();
}
到此为止,卡住了。不是因为不懂C++的缘故,而是因为理 论 知 识 太 欠 缺 了~~~~
所以还是好好的准备理论知识吧,大把大把的论文要看。我是看Mahony的和Paul的,现在主要是Paul的《Direction Cosine Matrix IMU: Theory》,讲的实在是太好了,搞无人机必看啊,这篇文章的最后给出了Mahony论文的下载地址。
高大上的理论
关于上面的这个Normalize the DCM matrix( 归一化处理)很有深度,值得了解一下其原理,在使用DCM控制和导航时,肯定存在积累数值的舍入误差、陀螺漂移误差、偏移误差、增益误差。它主要就是补偿抵消这几种误差(注意这几种误差 error)的;使用PI负反馈控制器检测这些误差,并在下一次产生之前就抵消这些误差(GPS检测yaw error,加速度计检测pitch和roll error)。在ardupilot源码中使用的Normalize算法就是来自2009年Paul的研究成果--Direction Cosine Matrix IMU: Theory。首先了解一下几个比较关键的概念。用下图先有个感性认识吧

1、陀螺漂移(Gyro drift)
由于外干扰力矩(机械摩擦、振动等因素)引起的陀螺自转轴的缓慢进动:陀螺漂移。通常,干扰力矩分为两类,与之对应的陀螺漂移也分为两类:一类干扰力矩是系统性的,规律已知,它引起规律性漂移,因而是可以通过计算机加以补偿的;另一类是随机因素造成的,它引起随机漂移。在实际应用中,除了要尽可能减小随机因素的影响外,对实验结果还要进行统计处理,以期对随机漂移作出标定,并通过系统来进行补偿。但由于它是无规律的,很难达到。 平时所说的用加速计(静态特性好)修正陀螺仪的漂移,其实这个修正是利用加速度计修正陀螺仪计(动态特性好)算出的姿态,并估计出陀螺仪的漂移,在下一次做姿态解算时,陀螺仪的输出减去估计出的漂移后再做捷联姿态解算,以此不断循环。融合的方法一般用EKF,KF也是基于最优估计的。
2、误差来源
在进行数值积分的过程中一定会引入数值误差,数值误差分为两类;一类是积分误差(来自于我们假设旋转速率在短时间内不变引起的),另一类是量化误差(主要来自于模数转换过程中引起的)。
3、旋转矩阵的约束
旋转矩阵就是改变方向不改变大小;旋转矩阵有9个元素,实际上是只有三个是独立的。由于旋转矩阵的正交性,意味着任何一对行或者列都是相互垂直的,并且每个行或者列的元素的平方和为1。所以在9个元素中有6个限制条件。

4、误差导致的结果
旋转矩阵的关键性能之一就是正交性,即在某个参考坐标系下的三个方向的向量两两垂直,且向量长度在每个参考系下都是等长的。数值误差会违背该性能,比如旋转矩阵的行和列都是单位向量,其长度都是1,但是由于数值误差的原因导致其长度边长或变短;最终致使它们缩小到0或者增长到无穷大,最后的结果就是导致原本相互正交的现在变的倾斜了。如下图所示。

那么问题来了,如何修正这个问题呢?可以使用如下方法( Ardupilot源码中就是利用如下算法处理的errors)。
5、如何消除各种误差(积累数值的舍入误差、陀螺漂移误差、偏移误差、增益误差)
其方法就是采样DCMIMU:Theory中提出的理论—强制正交化(也称为Renormalization)。 首先计算矩阵中X、Y行的点积(dotproduct),理论上应该是0,但是由于各种errors的影响,所以点积的值不是0,而表示为error。

然后把这个误差项分半交叉耦合到X、Y行上,如下公式。

通过上述两个公式处理过以后,正交误差明显减小了很多,即R旋转矩阵的每个行和列的长度都非常接近1。接下来就是调整旋转矩阵的Z行,使其与X、Y正交,方法比较简单,直接使用X、Y的叉积(cross product)即可。

最后一步就是放缩旋转矩阵的每一行使其长度等于1,现在用一种比较简单的方法实现,即使用泰勒展开。
ardupilot中的源码实现如下:
Void AP_AHRS_DCM::normalize(void)
{
float error;
Vector3f t0, t1, t2;
error = _dcm_matrix.a * _dcm_matrix.b; // eq.18
t0 = _dcm_matrix.a - (_dcm_matrix.b * (0.5f * error)); // eq.19
t1 = _dcm_matrix.b - (_dcm_matrix.a * (0.5f * error)); //eq.19
t2 = t0 % t1; // c= a x b // eq.20
if (!renorm(t0, _dcm_matrix.a) ||
!renorm(t1, _dcm_matrix.b) ||
!renorm(t2, _dcm_matrix.c)) {
// Our solution is blowing up and we will force back
// to last euler angles
_last_failure_ms = AP_HAL::millis();
AP_AHRS_DCM::reset(true);
}
}
结论
本篇博文没有介绍多少关于源代码的,主要就时觉得理论太欠缺了,接下来还有四元数,控制中主要还是用它做运算,还有各种滤波。接下来就是主要看关于姿态估计的了,姿态估计算法实现主要就是在PX4Firmware/src/modules/attitude_estimator_q中(q:quaternion),首先介绍一些代码执行顺序,方便后期有个良好的逻辑框架阅读代码和习惯。
1) 首先就是该文件中需要的头文件的包含;
2) 然后是一个C++的引用定义extern“C” __EXPORT int attitude_estimator_q_main(int argc, char *argv[]),可以根据这个attitude_estimator_q_main进行追踪到函数原型(754);
3) 在attitude_estimator_q_main函数中调用姿态估计的启动函数start()(775);
4) 详细介绍一下该启动函数,比较重要,源码中很多都是靠这种方法启动的,还记上次讲的sensor初始化么。源码如下。
int AttitudeEstimatorQ::start()
{
ASSERT(_control_task == -1);
/* start the task *//*POSIX接口的任务启动函数*/
_control_task = px4_task_spawn_cmd(“attitude_estimator_q”,
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
2100,
(px4_main_t)&AttitudeEstimatorQ::task_main_trampoline,
nullptr);
if (_control_task 《 0) {
warn(“task start failed”);
return -errno;
}
return OK;
}
5) 然后是task_main_trampoline函数,内部跳转到task_main()
好了,就是它了,慢慢研究吧,把这个里面的过程都研究透吧。
4、arducopter.cpp
分析ardupilot这套代码首先就是拿arducopter.cpp开刀,
Loop函数的设计框架既要准确,又要高效。总体设计是这样的:
其一用一个计时器定时触发测量;其二所有测量过程都靠中断推进;其三在main函数里不断检查测量是否完成,完成就进行解算。测量过程还是比较耗时间的,基于这样的设计,测量和解算可以同时进行,不会浪费CPU时间在(等待)测量上。而通过计时器触发测量,最大限度保证积分间隔的准确。
整个控制过程主要就集中在arducopter.cpp里面,首先就是scheduler_tasks[]中是需要创建的task线程,如下图中,接收机的rc_loop、arm_motors_check等,还记得上篇博文中介绍的解锁和上锁的操作么,就是在arm_motors_check函数中实现的,以固定的频率去采集遥控器信号。

1)setup函数
然后就是setup函数,在该函数中做的事情还是比较全面的,其中内部调用了一个比较重要的函数init_ardupilot(),该函数做了一系列的初始化,该初始化和上一篇博文介绍的不一样,上一篇主要是配置底层硬件的(如STM32、sensors),而此处的主要是飞行前的检测比那个初始化的晚;比如检测是否有USB连接、初始化UART、打印固件版本、初始化电源检测、初始化RSSI、注册mavlink服务、初始化log、初始化rc_in/out(内部含有电调校准)、初始化姿态/位置控制器、初始化飞行模式、初始化aux_switch、使能失控保护、配置dataflash最后打印“Ready to FLY ”。接下来就几个比较重要的函数(上述标红)进行深入分析。
void Copter::init_rc_in()
{
//rc_map 结合AC_RCMapper.h
channel_roll = RC_Channel::rc_channel(rcmap.roll()-1);
channel_pitch = RC_Channel::rc_channel(rcmap.pitch()-1);
channel_throttle = RC_Channel::rc_channel(rcmap.throttle()-1);
channel_yaw = RC_Channel::rc_channel(rcmap.yaw()-1);
// set rc channel ranges
channel_roll-》set_angle(ROLL_PITCH_INPUT_MAX);//4500
channel_pitch-》set_angle(ROLL_PITCH_INPUT_MAX);
channel_yaw-》set_angle(4500);
channel_throttle-》set_range(g.throttle_min, THR_MAX);//1000
channel_roll-》set_type(RC_CHANNEL_TYPE_ANGLE_RAW);
channel_pitch-》set_type(RC_CHANNEL_TYPE_ANGLE_RAW);
channel_yaw-》set_type(RC_CHANNEL_TYPE_ANGLE_RAW);
//set auxiliary servo ranges
g.rc_5.set_range_in(0,1000);
g.rc_6.set_range_in(0,1000);
g.rc_7.set_range_in(0,1000);
g.rc_8.set_range_in(0,1000);
// set default dead zones
default_dead_zones();
// initialise throttle_zero flag
ap.throttle_zero = true;//注意这个,rc_map好以后把油门配置为0
// true if the throttle stick is at zero, debounced, determines if pilot intends shut-down when not using motor interlock
}
// init_rc_out -- initialise motors and check if pilot wants to perform ESC calibration
void Copter::init_rc_out()
{
motors.set_update_rate(g.rc_speed);
motors.set_frame_orientation(g.frame_orientation);//配置机体类型(+/x)
motors.Init(); // motor initialisation
#if FRAME_CONFIG != HELI_FRAME
motors.set_throttle_range(g.throttle_min, channel_throttle-》radio_min, channel_throttle-》radio_max);//配置油门最大值和最小值 motors.set_hover_throttle(g.throttle_mid);
#endif
for(uint8_t i = 0; i 《 5; i++) {
delay(20);
read_radio();
}
// we want the input to be scaled correctly
channel_throttle-》set_range_out(0,1000);
// check if we should enter esc calibration mode
esc_calibration_startup_check();//电调校准,进入以后首先判断是否有pre-arm,如果没有则直接退出校准。校准过飞机的都知道这个
// enable output to motors
pre_arm_rc_checks();
if (ap.pre_arm_rc_check) {
enable_motor_output();//内部会调用motors.output_min()函数sends minimum values out to the motors,待会介绍该函数
}
// refresh auxiliary channel to function map
RC_Channel_aux::update_aux_servo_function();
// setup correct scaling for ESCs like the UAVCAN PX4ESC which
// take a proportion of speed.
hal.rcout-》set_esc_scaling(channel_throttle-》radio_min, channel_throttle-》radio_max);
}
简单介绍如何如何控制电机转动以及cork() and push(),并在此基础上测试了关于scheduler_tasks[] 中的任务的执行频率是否可以达到要求。测试方法:在scheduler_tasks[] 任务列表的throttle_task中添加一个累加标志位counterflag,每执行一次throttle_task任务就对齐加1,加到100时使电机转动,测试结果约为5S时电机转动,理论是50HZ的周期(不加执行时间是需要2S转动)再加上每次需要的执行时间以后还是比较理想的。
// output_min - sends minimum values out to the motors
void AP_MotorsMatrix::output_min()
{
int8_t i;
// set limits flags
limit.roll_pitch = true;
limit.yaw = true;
limit.throttle_lower = true;
limit.throttle_upper = false;
// fill the motor_out[] array for HIL use and send minimum value to each motor
hal.rcout-》cork();
/*Delay subsequent calls to write() going to the underlying hardware in
order to group related writes together. When all the needed writes are
done, call push() to commit the changes.
This method is optional: if the subclass doesn‘t implement it all calls
to write() are synchronous.*/
for( i=0; i《AP_MOTORS_MAX_NUM_MOTORS; i++ ) {
// AP_MOTORS_MAX_NUM_MOTORS=8
if( motor_enabled[i] ) {
rc_write(i, _throttle_radio_min);
//下面会解析rc_write(uint8_t chan, uint16_t pwm)
}
}
hal.rcout-》push();
/*Push pending changes to the underlying hardware. All changes between a call to cork() and push() are pushed together in a single transaction.This method is optional: if the subclass doesn’t implement it all calls to write() are synchronous.*/
}
//由上述可知在通过HAL层配置数据时使用cork() and push()函数包装需要单次传输的数据。该方法就是为了实现对四个电机同时配置,避免由for语句产生的延时,也是强调同步(synchronous)。
如下解析rc_write(uint8_t chan, uint16_t pwm)
void AP_Motors::rc_write(uint8_t chan, uint16_t pwm)
{
if (_motor_map_mask & (1U《《chan)) {
// we have a mapped motor number for this channel
chan = _motor_map[chan];// mapping to output channels
}
hal.rcout-》write(chan, pwm);//通过HAL层直接输出配置电调
}
Setup()函数的最后一句是fast_loopTimer = AP_HAL::micros(),获取micros()通过层层封装最终就是上篇博文中介绍的hrt,该时间会在下面的loop函数中使用。
2)loop函数
该函数比较重要,fast_loop和schedule_task都是封装在该函数中的,下面主要讲述fast_loop。
// Main loop - 400hz
void Copter::fast_loop()
{
// IMU DCM Algorithm 里面有个update函数,这个函数就是读取解算好的角度信息
read_AHRS();
// run low level rate controllers that only require IMU data
attitude_control.rate_controller_run();
// send outputs to the motors library
motors_output();
// Inertial Nav
read_inertia();
// check if ekf has reset target heading
check_ekf_yaw_reset();
// run the attitude controllers
update_flight_mode();
// update home from EKF if necessary
update_home_from_EKF();
// check if we‘ve landed or crashed
update_land_and_crash_detectors();
// log sensor health
if (should_log(MASK_LOG_ANY)) {
Log_Sensor_Health();
}
}
read_AHRS()内部使用ahrs.update更新AHRS数据。
// run a full DCM update round
Void AP_AHRS_DCM::update(void)
{
// tell the IMU to grab some data
_ins.update();//update gyro and accel values from backends具体实现过程详见源码
// ask the IMU how much time this sensor reading represents
delta_t = _ins.get_delta_time();
// Integrate the DCM matrix using gyro inputs
//使用陀螺仪数据更新DCM矩阵(方向余弦矩阵:direction-cosine-matrix ),使用刚刚测量出来的陀螺仪值、以及上个周期对陀螺仪的补偿值进行角度更新
matrix_update(delta_t);
// Normalize the DCM matrix 归一化处理
normalize();
// Perform drift correction
drift_correction(delta_t);
// paranoid check for bad values in the DCM matrix
check_matrix();
// Calculate pitch, roll, yaw for stabilization and navigation
euler_angles();
// update trig values including _cos_roll, cos_pitch
update_trig();
}
到此为止,卡住了。不是因为不懂C++的缘故,而是因为理 论 知 识 太 欠 缺 了~~~~
所以还是好好的准备理论知识吧,大把大把的论文要看。我是看Mahony的和Paul的,现在主要是Paul的《Direction Cosine Matrix IMU: Theory》,讲的实在是太好了,搞无人机必看啊,这篇文章的最后给出了Mahony论文的下载地址。
高大上的理论
关于上面的这个Normalize the DCM matrix( 归一化处理)很有深度,值得了解一下其原理,在使用DCM控制和导航时,肯定存在积累数值的舍入误差、陀螺漂移误差、偏移误差、增益误差。它主要就是补偿抵消这几种误差(注意这几种误差 error)的;使用PI负反馈控制器检测这些误差,并在下一次产生之前就抵消这些误差(GPS检测yaw error,加速度计检测pitch和roll error)。在ardupilot源码中使用的Normalize算法就是来自2009年Paul的研究成果--Direction Cosine Matrix IMU: Theory。首先了解一下几个比较关键的概念。用下图先有个感性认识吧

1、陀螺漂移(Gyro drift)
由于外干扰力矩(机械摩擦、振动等因素)引起的陀螺自转轴的缓慢进动:陀螺漂移。通常,干扰力矩分为两类,与之对应的陀螺漂移也分为两类:一类干扰力矩是系统性的,规律已知,它引起规律性漂移,因而是可以通过计算机加以补偿的;另一类是随机因素造成的,它引起随机漂移。在实际应用中,除了要尽可能减小随机因素的影响外,对实验结果还要进行统计处理,以期对随机漂移作出标定,并通过系统来进行补偿。但由于它是无规律的,很难达到。 平时所说的用加速计(静态特性好)修正陀螺仪的漂移,其实这个修正是利用加速度计修正陀螺仪计(动态特性好)算出的姿态,并估计出陀螺仪的漂移,在下一次做姿态解算时,陀螺仪的输出减去估计出的漂移后再做捷联姿态解算,以此不断循环。融合的方法一般用EKF,KF也是基于最优估计的。
2、误差来源
在进行数值积分的过程中一定会引入数值误差,数值误差分为两类;一类是积分误差(来自于我们假设旋转速率在短时间内不变引起的),另一类是量化误差(主要来自于模数转换过程中引起的)。
3、旋转矩阵的约束
旋转矩阵就是改变方向不改变大小;旋转矩阵有9个元素,实际上是只有三个是独立的。由于旋转矩阵的正交性,意味着任何一对行或者列都是相互垂直的,并且每个行或者列的元素的平方和为1。所以在9个元素中有6个限制条件。

4、误差导致的结果
旋转矩阵的关键性能之一就是正交性,即在某个参考坐标系下的三个方向的向量两两垂直,且向量长度在每个参考系下都是等长的。数值误差会违背该性能,比如旋转矩阵的行和列都是单位向量,其长度都是1,但是由于数值误差的原因导致其长度边长或变短;最终致使它们缩小到0或者增长到无穷大,最后的结果就是导致原本相互正交的现在变的倾斜了。如下图所示。

那么问题来了,如何修正这个问题呢?可以使用如下方法( Ardupilot源码中就是利用如下算法处理的errors)。
5、如何消除各种误差(积累数值的舍入误差、陀螺漂移误差、偏移误差、增益误差)
其方法就是采样DCMIMU:Theory中提出的理论—强制正交化(也称为Renormalization)。 首先计算矩阵中X、Y行的点积(dotproduct),理论上应该是0,但是由于各种errors的影响,所以点积的值不是0,而表示为error。

然后把这个误差项分半交叉耦合到X、Y行上,如下公式。

通过上述两个公式处理过以后,正交误差明显减小了很多,即R旋转矩阵的每个行和列的长度都非常接近1。接下来就是调整旋转矩阵的Z行,使其与X、Y正交,方法比较简单,直接使用X、Y的叉积(cross product)即可。

最后一步就是放缩旋转矩阵的每一行使其长度等于1,现在用一种比较简单的方法实现,即使用泰勒展开。
ardupilot中的源码实现如下:
Void AP_AHRS_DCM::normalize(void)
{
float error;
Vector3f t0, t1, t2;
error = _dcm_matrix.a * _dcm_matrix.b; // eq.18
t0 = _dcm_matrix.a - (_dcm_matrix.b * (0.5f * error)); // eq.19
t1 = _dcm_matrix.b - (_dcm_matrix.a * (0.5f * error)); //eq.19
t2 = t0 % t1; // c= a x b // eq.20
if (!renorm(t0, _dcm_matrix.a) ||
!renorm(t1, _dcm_matrix.b) ||
!renorm(t2, _dcm_matrix.c)) {
// Our solution is blowing up and we will force back
// to last euler angles
_last_failure_ms = AP_HAL::millis();
AP_AHRS_DCM::reset(true);
}
}
结论
本篇博文没有介绍多少关于源代码的,主要就时觉得理论太欠缺了,接下来还有四元数,控制中主要还是用它做运算,还有各种滤波。接下来就是主要看关于姿态估计的了,姿态估计算法实现主要就是在PX4Firmware/src/modules/attitude_estimator_q中(q:quaternion),首先介绍一些代码执行顺序,方便后期有个良好的逻辑框架阅读代码和习惯。
1) 首先就是该文件中需要的头文件的包含;
2) 然后是一个C++的引用定义extern“C” __EXPORT int attitude_estimator_q_main(int argc, char *argv[]),可以根据这个attitude_estimator_q_main进行追踪到函数原型(754);
3) 在attitude_estimator_q_main函数中调用姿态估计的启动函数start()(775);
4) 详细介绍一下该启动函数,比较重要,源码中很多都是靠这种方法启动的,还记上次讲的sensor初始化么。源码如下。
int AttitudeEstimatorQ::start()
{
ASSERT(_control_task == -1);
/* start the task *//*POSIX接口的任务启动函数*/
_control_task = px4_task_spawn_cmd(“attitude_estimator_q”,
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
2100,
(px4_main_t)&AttitudeEstimatorQ::task_main_trampoline,
nullptr);
if (_control_task 《 0) {
warn(“task start failed”);
return -errno;
}
return OK;
}
5) 然后是task_main_trampoline函数,内部跳转到task_main()
好了,就是它了,慢慢研究吧,把这个里面的过程都研究透吧。
举报