目录
摘要
本节主要记录自己学习ardupilot飞控代码的定点模式的过程,ardupilot定点模式有两种方式,第一种:留待模式定点,第二种模式:poshold模式定点,两种方式差别很大,第一种:控制无人机的运动加速度来实现位置控制,第二种:控制无人机的角度来实现位置控制。
1.留待模式初始化
(1)首先看张整体留待模式初始化流程图
(2)分析代码loiter_init()
bool Copter::loiter_init(bool ignore_checks)
{
// printf("WWW1\r\n");
if (position_ok() || ignore_checks) //定位信息OK,ignore_checks=1才可以设置,这是没有解锁的情况下
{
// printf("WWW2\r\n");
// printf("ignore_checks=%d\r\n",ignore_checks);
//设置当前的目标-------------------set target to current position
wp_nav->init_loiter_target();
//初始化垂直速度和加速度-------------- initialize vertical speed and acceleration
pos_control->set_speed_z(-g.pilot_velocity_z_max, g.pilot_velocity_z_max); //pilot_velocity_z_max=250cm/s
pos_control->set_accel_z(g.pilot_accel_z);
//初始化位置和目标速度----------------- initialise position and desired velocity
if (!pos_control->is_active_z()) //高度是否激活
{
pos_control->set_alt_target_to_current_alt();
pos_control->set_desired_velocity_z(inertial_nav.get_velocity_z());
}
return true;
}else
{
// printf("WWW3\r\n");
return false;
}
}
2.留待模式更新
case LOITER:
loiter_run(); //悬停模式运行,这里通过遥控器的遥感变化转换成加速度的控制
break;
(1)分析代码loiter_run():
void Copter::loiter_run()
{
LoiterModeState loiter_state; //声明悬停状态变量
float target_yaw_rate = 0.0f; //偏航目标速度变量
float target_climb_rate = 0.0f; //目标爬升率
float takeoff_climb_rate = 0.0f; //起飞爬升率
//初始化垂直速度和加速度----------- initialize vertical speed and acceleration
pos_control->set_speed_z(-g.pilot_velocity_z_max, g.pilot_velocity_z_max);
pos_control->set_accel_z(g.pilot_accel_z);
// 处理飞行输入信号,当我们的遥控信号输入没有失败--------process pilot inputs unless we are in radio failsafe
if (!failsafe.radio)
{
//简单模式变换在导频输入中的应用------------------apply SIMPLE mode transform to pilot inputs
update_simple_mode();
//处理飞行横滚和俯仰的输入------------------------process pilot's roll and pitch input
wp_nav->set_pilot_desired_acceleration(channel_roll->get_control_in(), channel_pitch->get_control_in());
//处理飞机航向的输入得到飞机的航向期望角速度---------get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
//获取爬升速率---------------------------------get pilot desired climb rate
target_climb_rate = get_pilot_desired_climb_rate(channel_throttle->get_control_in());
target_climb_rate = constrain_float(target_climb_rate, -g.pilot_velocity_z_max, g.pilot_velocity_z_max);
} else
{
// clear out pilot desired acceleration in case radio failsafe event occurs and we do not switch to RTL for some reason
//在发生无线电故障安全事件时清除飞行员期望的加速度,并且由于某种原因,我们不切换到RTL。
wp_nav->clear_pilot_desired_acceleration();
}
//如果我们着陆,清除期望目标---------------------relax loiter target if we might be landed
if (ap.land_complete_maybe)
{
wp_nav->loiter_soften_for_landing();
}
#if FRAME_CONFIG == HELI_FRAME
// helicopters are held on the ground until rotor speed runup has finished
bool takeoff_triggered = (ap.land_complete && (target_climb_rate > 0.0f) && motors->rotor_runup_complete());
#else
bool takeoff_triggered = ap.land_complete && (target_climb_rate > 0.0f);
#endif
/******************************模式检查**********************************************************/
/******************************模式检查**********************************************************/
//根据不同的情况,赋值悬停模式标志不同-------------Loiter State Machine Determination
if (!motors->armed() || !motors->get_interlock())
{
loiter_state = Loiter_MotorStopped; //电机停转
} else if (takeoff_state.running || takeoff_triggered)
{
loiter_state = Loiter_Takeoff; //起飞
} else if (!ap.auto_armed || ap.land_complete)
{
loiter_state = Loiter_Landed; //着落
} else
{
loiter_state = Loiter_Flying; //飞行
}
/******************************模式检查**********************************************************/
/******************************模式检查**********************************************************/
// Loiter State Machine
switch (loiter_state)
{
case Loiter_MotorStopped:
motors->set_desired_spool_state(AP_Motors::DESIRED_SHUT_DOWN);
#if FRAME_CONFIG == HELI_FRAME
// force descent rate and call position controller
pos_control->set_alt_target_from_climb_rate(-abs(g.land_speed), G_Dt, false);
#else
wp_nav->init_loiter_target();
attitude_control->reset_rate_controller_I_terms();
attitude_control->set_yaw_target_to_current_heading();
pos_control->relax_alt_hold_controllers(0.0f); // forces throttle output to go to zero
#endif
wp_nav->update_loiter(ekfGndSpdLimit, ekfNavVelGainScaler); //导航悬停控制
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(wp_nav->get_roll(), wp_nav->get_pitch(), target_yaw_rate, get_smoothing_gain());
pos_control->update_z_controller();
break;
case Loiter_Takeoff:
// set motors to full range
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
// initiate take-off
if (!takeoff_state.running)
{
takeoff_timer_start(constrain_float(g.pilot_takeoff_alt,0.0f,1000.0f));
// indicate we are taking off
set_land_complete(false);
// clear i term when we're taking off
set_throttle_takeoff();
}
// get takeoff adjusted pilot and takeoff climb rates
takeoff_get_climb_rates(target_climb_rate, takeoff_climb_rate);
// get avoidance adjusted climb rate
target_climb_rate = get_avoidance_adjusted_climbrate(target_climb_rate);
// run loiter controller
wp_nav->update_loiter(ekfGndSpdLimit, ekfNavVelGainScaler);
// call attitude controller
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(wp_nav->get_roll(), wp_nav->get_pitch(), target_yaw_rate, get_smoothing_gain());
// update altitude target and call position controller
pos_control->set_alt_target_from_climb_rate_ff(target_climb_rate, G_Dt, false);
pos_control->add_takeoff_climb_rate(takeoff_climb_rate, G_Dt);
pos_control->update_z_controller();
break;
case Loiter_Landed:
// set motors to spin-when-armed if throttle below deadzone, otherwise full range (but motors will only spin at min throttle)
if (target_climb_rate < 0.0f) {
motors->set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
} else {
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
}
wp_nav->init_loiter_target();
attitude_control->reset_rate_controller_I_terms();
attitude_control->set_yaw_target_to_current_heading();
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(0, 0, 0, get_smoothing_gain());
pos_control->relax_alt_hold_controllers(0.0f); // forces throttle output to go to zero
pos_control->update_z_controller();
break;
case Loiter_Flying: //飞行处理
//将电机设置为全范围------set motors to full range
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
#if PRECISION_LANDING == ENABLED
if (do_precision_loiter()) //精确降落使能了,就可以进行精确悬停位置控制器
{
precision_loiter_xy();
}
#endif
//运行悬停控制器-----------run loiter controller
wp_nav->update_loiter(ekfGndSpdLimit, ekfNavVelGainScaler); //获取_pitch_target,_roll_target
//运行姿态控制器-----------call attitude controller
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(wp_nav->get_roll(), wp_nav->get_pitch(), target_yaw_rate, get_smoothing_gain());
//利用测距仪器调整爬升率-----adjust climb rate using rangefinder
if (rangefinder_alt_ok())
{
// if rangefinder is ok, use surface tracking
target_climb_rate = get_surface_tracking_climb_rate(target_climb_rate, pos_control->get_alt_target(), G_Dt);
}
// get avoidance adjusted climb rate
target_climb_rate = get_avoidance_adjusted_climbrate(target_climb_rate);
//更新高度目标和好找位置控制器----------update altitude target and call position controller
pos_control->set_alt_target_from_climb_rate_ff(target_climb_rate, G_Dt, false);
pos_control->update_z_controller();
break;
}
}
重点分析代码中的函数:
《1》分析第一个函数:
wp_nav->set_pilot_desired_acceleration(channel_roll->get_control_in(), channel_pitch->get_control_in());
从代码可以看出当我们摇杆达到最大时无人机的运动的加速度的最大值有_loiter_accel_cmss来确定
其中:
AP_GROUPINFO(“LOIT_MAXA”, 8, AC_WPNav, _loiter_accel_cmss, WPNAV_LOITER_ACCEL),
#define WPNAV_LOITER_ACCEL 250.0f // default acceleration in loiter mode
可以看出代码默认设置的无人机运动加速度是2.5m/s/s
我们重点关心两个值:
无人机前进加速度:_pilot_accel_fwd_cms
左右加速度:_pilot_accel_rgt_cms
《2》分析第一个函数:
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in()); //获取无人机偏航角速度
float Copter::get_pilot_desired_yaw_rate(int16_t stick_angle)
{
float yaw_request;
// 计算偏航速率需求-----calculate yaw rate request
if (g2.acro_y_expo <= 0)
{
yaw_request = stick_angle * g.acro_yaw_p; //g.acro_yaw_p=4.5
} else
{
// expo variables
float y_in, y_in3, y_out;
// range check expo
if (g2.acro_y_expo > 1.0f || g2.acro_y_expo < 0.5f)
{
g2.acro_y_expo = 1.0f;
}
// yaw expo
y_in = float(stick_angle)/ROLL_PITCH_YAW_INPUT_MAX;
y_in3 = y_in*y_in*y_in;
y_out = (g2.acro_y_expo * y_in3) + ((1.0f - g2.acro_y_expo) * y_in);
yaw_request = ROLL_PITCH_YAW_INPUT_MAX * y_out * g.acro_yaw_p;
}
// convert pilot input to the desired yaw rate
return yaw_request;
}