void loop()
{
// We want this to execute at 50Hz if possible
// -------------------------------------------
if (millis()-fast_loopTimer > 19) 1
{
delta_ms_fast_loop = millis() - fast_loopTimer; 2
load= (float)(fast_loopTimeStamp - fast_loopTimer)/delta_ms_fast_loop; //cpu使用率 3
G_Dt=(float)delta_ms_fast_loop/1000.f; //陀螺仪积分时间(DCM算法) 4
fast_loopTimer = millis(); 5
mainLoop_count++; 6
// Execute the fast loop
// ---------------------
fast_loop(); 7
// Execute the medium loop
// -----------------------
medium_loop(); 8
counter_one_herz++; 9
if(counter_one_herz == 50) 10
{
one_second_loop(); 11
counter_one_herz = 0; 12
}
if(millis()-perf_mon_timer>20000) 13
{ //性能监控时间到,执行性能监控
if (mainLoop_count != 0) 14
{
gcs.send_message(MSG_PERF_REPORT); 15
if (g.log_bitmask & MASK_LOG_PM) 16
Log_Write_Performance(); 17
resetPerfData(); 18
}
}
fast_loopTimeStamp = millis(); 19
}
}
void fast_loop()
{
// This is the fast loop - we want it to execute at 50Hz if possible
// -----------------------------------------------------------------
if (delta_ms_fast_loop > G_Dt_max)
G_Dt_max = delta_ms_fast_loop;
// Read radio ////读取遥控信号
// ----------
read_radio(); //APM_RC.InputCh(CH_ROLL)-> ch1_temp-> g.channel_roll.set_pwm(ch1_temp)(即转为control_in)
//油门还有control_failsafe(g.channel_throttle.radio_in);
//g.channel_throttle.servo_out = g.channel_throttle.control_in;
//airspeed_nudge,throttle_nudge,
// check for loss of control signal failsafe condition ////检查丢失控制信号故障安
// ------------------------------------
check_short_failsafe(); //关于failsafe和ch3_failsafe的处理
// Read Airspeed ///读取空速
// -------------
if (g.airspeed_enabled == true && HIL_MODE != HIL_MODE_ATTITUDE)
{ //使能空速计真实飞行时为1
read_airspeed(); //读取空速,并calc_airspeed_errors();
}
else if (g.airspeed_enabled == true && HIL_MODE == HIL_MODE_ATTITUDE)
{ //真实飞行时为0
calc_airspeed_errors();
}
#if HIL_MODE == HIL_MODE_SENSORS //飞行模式时为0
// update hil before dcm update
hil.update();
#endif
dcm.update_DCM(G_Dt); ////更新DCM
// uses the yaw from the DCM to give more accurate turns ///使用从DCM获得的偏航数据,进行更精确的转弯
calc_bearing_error(); //计算得出bearing_error
# if HIL_MODE == HIL_MODE_DISABLED //飞行模式时为1
if (g.log_bitmask & MASK_LOG_ATTITUDE_FAST)
Log_Write_Attitude((int)dcm.roll_sensor, (int)dcm.pitch_sensor, (uint16_t)dcm.yaw_sensor);
if (g.log_bitmask & MASK_LOG_RAW)
Log_Write_Raw();
#endif
// inertial navigation ////惯性导航
// ------------------
#if INERTIAL_NAVIGATION == ENABLED //这个不执行。本程序的捷联惯性导航算法只能计算飞机飞行姿态,无法结算三维位置,,所以,不能实施完全的惯性导航。或者程序作者正在进行相关试验,或者程序作者的惯性导航不是这个意思,仅是调试时调用这个。
// TODO: implement inertial nav function //实施惯性导航功能
inertialNavigation();
#endif
// custom code/exceptions for flight modes ///飞行模式的自定义代码/异常
// ---------------------------------------
update_current_flight_mode(); // 导航级PID
// apply desired roll, pitch and yaw to the plane ////控制飞机的副翼,升降,方向 if (control_mode > MANUAL) stabilize(); // 控制级PID //write out the servo PWM values
//
set_servos_4();
// XXX is it appropriate to be doing the comms below on the fast loop? ////现在适合做快速环路上的COMMS吗?
#if HIL_MODE != HIL_MODE_DISABLED && HIL_PORT != GCS_PORT //飞行模式时为0
// kick the HIL to process incoming sensor packets //使用HIL处理传入的传感器数据包
hil.update();
#if HIL_PROTOCOL == HIL_PROTOCOL_MAVLINK
hil.data_stream_send(45,1000);
#else
hil.send_message(MSG_SERVO_OUT);
#endif
#elif HIL_PROTOCOL == HIL_PROTOCOL_MAVLINK && HIL_MODE == HIL_MODE_DISABLED && HIL_PORT == 0 //飞行模式时为1
// Case for hil object on port 0 just for mission planning //HIL端口的对象,只是用来进行任务规划
hil.update();
hil.data_stream_send(45,1000);
#endif
// kick the GCS to process uplink data ////让GCS处理上行数据
gcs.update();
#if GCS_PROTOCOL == GCS_PROTOCOL_MAVLINK //飞行模式时为
gcs.data_stream_send(45,1000);
#endif
// XXX this should be absorbed into the above,
// or be a "GCS fast loop" interface
}
[修改于 8年5个月前 - 2016/08/26 22:03:00]