mirror of https://github.com/ArduPilot/ardupilot
Copter: make surface tracking adjust_climb_rate take a float
Its callers all pass in floats and we return a float, so stop going via an int16_t
This commit is contained in:
parent
b0428f0fe8
commit
c0e8d319c6
|
@ -122,7 +122,7 @@ float Copter::get_non_takeoff_throttle()
|
|||
// adjust_climb_rate - hold copter at the desired distance above the
|
||||
// ground; returns climb rate (in cm/s) which should be passed to
|
||||
// the position controller
|
||||
float Copter::SurfaceTracking::adjust_climb_rate(int16_t target_rate)
|
||||
float Copter::SurfaceTracking::adjust_climb_rate(float target_rate)
|
||||
{
|
||||
#if RANGEFINDER_ENABLED == ENABLED
|
||||
if (!copter.rangefinder_alt_ok()) {
|
||||
|
@ -184,7 +184,7 @@ float Copter::SurfaceTracking::adjust_climb_rate(int16_t target_rate)
|
|||
// return combined pilot climb rate + rate to correct rangefinder alt error
|
||||
return (target_rate + velocity_correction);
|
||||
#else
|
||||
return (float)target_rate;
|
||||
return target_rate;
|
||||
#endif
|
||||
}
|
||||
|
||||
|
|
|
@ -289,7 +289,7 @@ private:
|
|||
|
||||
class SurfaceTracking {
|
||||
public:
|
||||
float adjust_climb_rate(int16_t target_rate);
|
||||
float adjust_climb_rate(float target_rate);
|
||||
bool get_target_alt_cm(float &target_alt_cm) const;
|
||||
void set_target_alt_cm(float target_alt_cm);
|
||||
float logging_target_alt() const {
|
||||
|
|
Loading…
Reference in New Issue