mirror of https://github.com/ArduPilot/ardupilot
Copter: use loop rate for copter
this allows for SCHED_LOOP_RATE below 400 in SITL for copter
This commit is contained in:
parent
255bda9f9c
commit
86d8450666
|
@ -43,7 +43,7 @@ void Copter::crash_check()
|
|||
crash_counter++;
|
||||
|
||||
// check if crashing for 2 seconds
|
||||
if (crash_counter >= (CRASH_CHECK_TRIGGER_SEC * MAIN_LOOP_RATE)) {
|
||||
if (crash_counter >= (CRASH_CHECK_TRIGGER_SEC * scheduler.get_loop_rate_hz())) {
|
||||
// log an error in the dataflash
|
||||
Log_Write_Error(ERROR_SUBSYSTEM_CRASH_CHECK, ERROR_CODE_CRASH_CHECK_CRASH);
|
||||
// send message to gcs
|
||||
|
@ -106,7 +106,7 @@ void Copter::parachute_check()
|
|||
}
|
||||
|
||||
// increment counter
|
||||
if (control_loss_count < (PARACHUTE_CHECK_TRIGGER_SEC*MAIN_LOOP_RATE)) {
|
||||
if (control_loss_count < (PARACHUTE_CHECK_TRIGGER_SEC*scheduler.get_loop_rate_hz())) {
|
||||
control_loss_count++;
|
||||
}
|
||||
|
||||
|
@ -122,7 +122,7 @@ void Copter::parachute_check()
|
|||
// To-Do: add check that the vehicle is actually falling
|
||||
|
||||
// check if loss of control for at least 1 second
|
||||
} else if (control_loss_count >= (PARACHUTE_CHECK_TRIGGER_SEC*MAIN_LOOP_RATE)) {
|
||||
} else if (control_loss_count >= (PARACHUTE_CHECK_TRIGGER_SEC*scheduler.get_loop_rate_hz())) {
|
||||
// reset control loss counter
|
||||
control_loss_count = 0;
|
||||
// log an error in the dataflash
|
||||
|
|
|
@ -87,10 +87,10 @@ void Copter::update_heli_control_dynamics(void)
|
|||
// if we are not landed and motor power is demanded, increment slew scalar
|
||||
hover_roll_trim_scalar_slew++;
|
||||
}
|
||||
hover_roll_trim_scalar_slew = constrain_int16(hover_roll_trim_scalar_slew, 0, MAIN_LOOP_RATE);
|
||||
hover_roll_trim_scalar_slew = constrain_int16(hover_roll_trim_scalar_slew, 0, scheduler.get_loop_rate_hz());
|
||||
|
||||
// set hover roll trim scalar, will ramp from 0 to 1 over 1 second after we think helicopter has taken off
|
||||
attitude_control.set_hover_roll_trim_scalar((float)(hover_roll_trim_scalar_slew/MAIN_LOOP_RATE));
|
||||
attitude_control.set_hover_roll_trim_scalar((float)(hover_roll_trim_scalar_slew/scheduler.get_loop_rate_hz()));
|
||||
}
|
||||
|
||||
// heli_update_landing_swash - sets swash plate flag so higher minimum is used when landed or landing
|
||||
|
|
|
@ -65,7 +65,7 @@ void Copter::update_land_detector()
|
|||
|
||||
if (motor_at_lower_limit && accel_stationary) {
|
||||
// landed criteria met - increment the counter and check if we've triggered
|
||||
if( land_detector_count < ((float)LAND_DETECTOR_TRIGGER_SEC)*MAIN_LOOP_RATE) {
|
||||
if( land_detector_count < ((float)LAND_DETECTOR_TRIGGER_SEC)*scheduler.get_loop_rate_hz()) {
|
||||
land_detector_count++;
|
||||
} else {
|
||||
set_land_complete(true);
|
||||
|
@ -76,7 +76,7 @@ void Copter::update_land_detector()
|
|||
}
|
||||
}
|
||||
|
||||
set_land_complete_maybe(ap.land_complete || (land_detector_count >= LAND_DETECTOR_MAYBE_TRIGGER_SEC*MAIN_LOOP_RATE));
|
||||
set_land_complete_maybe(ap.land_complete || (land_detector_count >= LAND_DETECTOR_MAYBE_TRIGGER_SEC*scheduler.get_loop_rate_hz()));
|
||||
}
|
||||
|
||||
// set land_complete flag and disarm motors if disarm-on-land is configured
|
||||
|
|
|
@ -56,6 +56,7 @@ void Copter::init_rc_out()
|
|||
{
|
||||
motors.set_update_rate(g.rc_speed);
|
||||
motors.set_frame_orientation(g.frame_orientation);
|
||||
motors.set_loop_rate(scheduler.get_loop_rate_hz());
|
||||
motors.Init(); // motor initialisation
|
||||
#if FRAME_CONFIG != HELI_FRAME
|
||||
motors.set_throttle_range(g.throttle_min, channel_throttle->get_radio_min(), channel_throttle->get_radio_max());
|
||||
|
|
Loading…
Reference in New Issue