mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-21 11:47:34 +08:00
Merge branch 'master' into seatbelt_multirotor
This commit is contained in:
@@ -282,7 +282,7 @@ void tune_error(void)
|
||||
|
||||
void do_rc_calibration(int status_pub, struct vehicle_status_s *status)
|
||||
{
|
||||
if (current_status.offboard_control_signal_lost) {
|
||||
if (current_status.rc_signal_lost) {
|
||||
mavlink_log_critical(mavlink_fd, "TRIM CAL: ABORT. No RC signal.");
|
||||
return;
|
||||
}
|
||||
|
||||
@@ -62,7 +62,7 @@ float calc_indicated_airspeed(float differential_pressure)
|
||||
if (differential_pressure > 0) {
|
||||
return sqrtf((2.0f*differential_pressure) / CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C);
|
||||
} else {
|
||||
return -sqrtf((2.0f*fabs(differential_pressure)) / CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C);
|
||||
return -sqrtf((2.0f*fabsf(differential_pressure)) / CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C);
|
||||
}
|
||||
|
||||
}
|
||||
@@ -106,6 +106,6 @@ float calc_true_airspeed(float total_pressure, float static_pressure, float temp
|
||||
return sqrtf((2.0f*(pressure_difference)) / density);
|
||||
} else
|
||||
{
|
||||
return -sqrtf((2.0f*fabs(pressure_difference)) / density);
|
||||
return -sqrtf((2.0f*fabsf(pressure_difference)) / density);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -63,7 +63,8 @@
|
||||
|
||||
enum ESC_VENDOR {
|
||||
ESC_VENDOR_GENERIC = 0, /**< generic ESC */
|
||||
ESC_VENDOR_MIKROKOPTER /**< Mikrokopter */
|
||||
ESC_VENDOR_MIKROKOPTER, /**< Mikrokopter */
|
||||
ESC_VENDOR_GRAUPNER_HOTT /**< Graupner HoTT ESC */
|
||||
};
|
||||
|
||||
enum ESC_CONNECTION_TYPE {
|
||||
|
||||
Reference in New Issue
Block a user