mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
Copter: log sonar_alt even when disabled
This commit is contained in:
parent
5644dd8620
commit
82ad454864
@ -74,7 +74,7 @@ void Copter::althold_run()
|
||||
// body-frame rate controller is run directly from 100hz loop
|
||||
|
||||
// call throttle controller
|
||||
if (sonar_alt_health >= SONAR_ALT_HEALTH_MAX) {
|
||||
if (sonar_enabled && (sonar_alt_health >= SONAR_ALT_HEALTH_MAX)) {
|
||||
// if sonar is ok, use surface tracking
|
||||
target_climb_rate = get_surface_tracking_climb_rate(target_climb_rate, pos_control.get_alt_target(), G_Dt);
|
||||
}
|
||||
|
@ -73,7 +73,7 @@ void Copter::circle_run()
|
||||
}
|
||||
|
||||
// run altitude controller
|
||||
if (sonar_alt_health >= SONAR_ALT_HEALTH_MAX) {
|
||||
if (sonar_enabled && (sonar_alt_health >= SONAR_ALT_HEALTH_MAX)) {
|
||||
// if sonar is ok, use surface tracking
|
||||
target_climb_rate = get_surface_tracking_climb_rate(target_climb_rate, pos_control.get_alt_target(), G_Dt);
|
||||
}
|
||||
|
@ -98,7 +98,7 @@ void Copter::loiter_run()
|
||||
// body-frame rate controller is run directly from 100hz loop
|
||||
|
||||
// run altitude controller
|
||||
if (sonar_alt_health >= SONAR_ALT_HEALTH_MAX) {
|
||||
if (sonar_enabled && (sonar_alt_health >= SONAR_ALT_HEALTH_MAX)) {
|
||||
// if sonar is ok, use surface tracking
|
||||
target_climb_rate = get_surface_tracking_climb_rate(target_climb_rate, pos_control.get_alt_target(), G_Dt);
|
||||
}
|
||||
|
@ -505,7 +505,7 @@ void Copter::poshold_run()
|
||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw(poshold.roll, poshold.pitch, target_yaw_rate);
|
||||
|
||||
// throttle control
|
||||
if (sonar_alt_health >= SONAR_ALT_HEALTH_MAX) {
|
||||
if (sonar_enabled && (sonar_alt_health >= SONAR_ALT_HEALTH_MAX)) {
|
||||
// if sonar is ok, use surface tracking
|
||||
target_climb_rate = get_surface_tracking_climb_rate(target_climb_rate, pos_control.get_alt_target(), G_Dt);
|
||||
}
|
||||
|
@ -95,7 +95,7 @@ void Copter::sport_run()
|
||||
attitude_control.rate_ef_roll_pitch_yaw(target_roll_rate, target_pitch_rate, target_yaw_rate);
|
||||
|
||||
// call throttle controller
|
||||
if (sonar_alt_health >= SONAR_ALT_HEALTH_MAX) {
|
||||
if (sonar_enabled && (sonar_alt_health >= SONAR_ALT_HEALTH_MAX)) {
|
||||
// if sonar is ok, use surface tracking
|
||||
target_climb_rate = get_surface_tracking_climb_rate(target_climb_rate, pos_control.get_alt_target(), G_Dt);
|
||||
}
|
||||
|
@ -40,7 +40,7 @@ int16_t Copter::read_sonar(void)
|
||||
sonar.update();
|
||||
|
||||
// exit immediately if sonar is disabled
|
||||
if (!sonar_enabled || (sonar.status() != RangeFinder::RangeFinder_Good)) {
|
||||
if (sonar.status() != RangeFinder::RangeFinder_Good) {
|
||||
sonar_alt_health = 0;
|
||||
return 0;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user