mirror of https://github.com/ArduPilot/ardupilot
ArduPlane: convert MIN_GNDSPEED_CM to MIN_GROUNDSPEED
This commit is contained in:
parent
1f7f4bac73
commit
5723b1c780
|
@ -637,12 +637,12 @@ const AP_Param::Info Plane::var_info[] = {
|
|||
// @User: Advanced
|
||||
GSCALAR(scaling_speed, "SCALING_SPEED", SCALING_SPEED),
|
||||
|
||||
// @Param: MIN_GNDSPD_CM
|
||||
// @Param: MIN_GROUNDSPEED
|
||||
// @DisplayName: Minimum ground speed
|
||||
// @Description: Minimum ground speed in cm/s when under airspeed control
|
||||
// @Units: cm/s
|
||||
// @Units: m/s
|
||||
// @User: Advanced
|
||||
ASCALAR(min_gndspeed_cm, "MIN_GNDSPD_CM", MIN_GNDSPEED_CM),
|
||||
ASCALAR(min_groundspeed, "MIN_GROUNDSPEED", MIN_GROUNDSPEED),
|
||||
|
||||
// @Param: TRIM_PITCH_DEG
|
||||
// @DisplayName: Pitch angle offset
|
||||
|
@ -1549,6 +1549,7 @@ void Plane::load_parameters(void)
|
|||
// Convert _CM (centimeter) parameters to meters and _CD (centidegrees) parameters to meters
|
||||
g.pitch_trim.convert_centi_parameter(AP_PARAM_INT16);
|
||||
aparm.airspeed_cruise.convert_centi_parameter(AP_PARAM_INT32);
|
||||
aparm.min_groundspeed.convert_centi_parameter(AP_PARAM_INT32);
|
||||
|
||||
hal.console->printf("load_all took %uus\n", (unsigned)(micros() - before));
|
||||
}
|
||||
|
|
|
@ -219,7 +219,7 @@ public:
|
|||
k_param_airspeed_cruise,
|
||||
k_param_RTL_altitude_cm,
|
||||
k_param_inverted_flight_ch_unused, // unused
|
||||
k_param_min_gndspeed_cm,
|
||||
k_param_min_groundspeed,
|
||||
k_param_crosstrack_use_wind, // unused
|
||||
|
||||
|
||||
|
|
|
@ -977,7 +977,7 @@ bool Plane::do_change_speed(uint8_t speedtype, float speed_target_ms, float thro
|
|||
break;
|
||||
case 1: // Ground speed
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Set groundspeed %u", (unsigned)speed_target_ms);
|
||||
aparm.min_gndspeed_cm.set(speed_target_ms * 100);
|
||||
aparm.min_groundspeed.set(speed_target_ms);
|
||||
return true;
|
||||
}
|
||||
|
||||
|
|
|
@ -118,12 +118,11 @@
|
|||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// MIN_GNDSPEED
|
||||
// MIN_GROUNDSPEED
|
||||
//
|
||||
#ifndef MIN_GNDSPEED
|
||||
# define MIN_GNDSPEED 0 // m/s (0 disables)
|
||||
#ifndef MIN_GROUNDSPEED
|
||||
# define MIN_GROUNDSPEED 0 // m/s (0 disables)
|
||||
#endif
|
||||
#define MIN_GNDSPEED_CM MIN_GNDSPEED*100
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
|
|
@ -18,7 +18,7 @@ void Plane::update_is_flying_5Hz(void)
|
|||
bool is_flying_bool = false;
|
||||
uint32_t now_ms = AP_HAL::millis();
|
||||
|
||||
uint32_t ground_speed_thresh_cm = (aparm.min_gndspeed_cm > 0) ? ((uint32_t)(aparm.min_gndspeed_cm*0.9f)) : GPS_IS_FLYING_SPEED_CMS;
|
||||
uint32_t ground_speed_thresh_cm = (aparm.min_groundspeed > 0) ? ((uint32_t)(aparm.min_groundspeed*90)) : GPS_IS_FLYING_SPEED_CMS;
|
||||
bool gps_confirmed_movement = (gps.status() >= AP_GPS::GPS_OK_FIX_3D) &&
|
||||
(gps.ground_speed_cm() >= ground_speed_thresh_cm);
|
||||
|
||||
|
|
|
@ -286,8 +286,8 @@ void Plane::calc_gndspeed_undershoot()
|
|||
if (!yawVect.is_zero()) {
|
||||
yawVect.normalize();
|
||||
float gndSpdFwd = yawVect * velNED.xy();
|
||||
groundspeed_undershoot_is_valid = aparm.min_gndspeed_cm > 0;
|
||||
groundspeed_undershoot = groundspeed_undershoot_is_valid ? (aparm.min_gndspeed_cm - gndSpdFwd*100) : 0;
|
||||
groundspeed_undershoot_is_valid = aparm.min_groundspeed > 0;
|
||||
groundspeed_undershoot = groundspeed_undershoot_is_valid ? (aparm.min_groundspeed*100 - gndSpdFwd*100) : 0;
|
||||
}
|
||||
} else {
|
||||
groundspeed_undershoot_is_valid = false;
|
||||
|
|
Loading…
Reference in New Issue