mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Motors:Heli Governor - change rotor_rpm argument to a float
This commit is contained in:
parent
f1a32d7872
commit
b6bfc8947f
@ -93,7 +93,7 @@ public:
|
||||
float get_rsc_setpoint() const { return _rsc_setpoint * 0.001f; }
|
||||
|
||||
// set_rpm - for rotor speed governor
|
||||
virtual void set_rpm(int16_t rotor_rpm) = 0;
|
||||
virtual void set_rpm(float rotor_rpm) = 0;
|
||||
|
||||
// set_desired_rotor_speed - sets target rotor speed as a number from 0 ~ 1
|
||||
virtual void set_desired_rotor_speed(float desired_speed) = 0;
|
||||
|
@ -207,7 +207,7 @@ void AP_MotorsHeli_Dual::set_desired_rotor_speed(float desired_speed)
|
||||
}
|
||||
|
||||
// set_rotor_rpm - used for governor with speed sensor
|
||||
void AP_MotorsHeli_Dual::set_rpm(int16_t rotor_rpm)
|
||||
void AP_MotorsHeli_Dual::set_rpm(float rotor_rpm)
|
||||
{
|
||||
_rotor.set_rotor_rpm(rotor_rpm);
|
||||
}
|
||||
|
@ -59,7 +59,7 @@ public:
|
||||
void output_to_motors() override;
|
||||
|
||||
// set_rpm - for rotor speed governor
|
||||
void set_rpm(int16_t rotor_rpm) override;
|
||||
void set_rpm(float rotor_rpm) override;
|
||||
|
||||
// set_desired_rotor_speed - sets target rotor speed as a number from 0 ~ 1000
|
||||
void set_desired_rotor_speed(float desired_speed) override;
|
||||
|
@ -97,7 +97,7 @@ void AP_MotorsHeli_Quad::set_desired_rotor_speed(float desired_speed)
|
||||
}
|
||||
|
||||
// set_rotor_rpm - used for governor with speed sensor
|
||||
void AP_MotorsHeli_Quad::set_rpm(int16_t rotor_rpm)
|
||||
void AP_MotorsHeli_Quad::set_rpm(float rotor_rpm)
|
||||
{
|
||||
_rotor.set_rotor_rpm(rotor_rpm);
|
||||
}
|
||||
|
@ -40,7 +40,7 @@ public:
|
||||
void output_to_motors() override;
|
||||
|
||||
// set_rpm - for rotor speed governor
|
||||
void set_rpm(int16_t rotor_rpm) override;
|
||||
void set_rpm(float rotor_rpm) override;
|
||||
|
||||
// set_desired_rotor_speed - sets target rotor speed as a number from 0 ~ 1000
|
||||
void set_desired_rotor_speed(float desired_speed) override;
|
||||
|
@ -84,7 +84,7 @@ public:
|
||||
float get_rotor_speed() const;
|
||||
|
||||
// set_rotor_rpm - when speed sensor is available for governor
|
||||
void set_rotor_rpm(int16_t rotor_rpm) {_rotor_rpm = (float)rotor_rpm; }
|
||||
void set_rotor_rpm(float rotor_rpm) {_rotor_rpm = (float)rotor_rpm; }
|
||||
|
||||
// get_governor_output
|
||||
float get_governor_output() const { return _governor_output; }
|
||||
|
@ -210,7 +210,7 @@ void AP_MotorsHeli_Single::set_desired_rotor_speed(float desired_speed)
|
||||
}
|
||||
|
||||
// set_rotor_rpm - used for governor with speed sensor
|
||||
void AP_MotorsHeli_Single::set_rpm(int16_t rotor_rpm)
|
||||
void AP_MotorsHeli_Single::set_rpm(float rotor_rpm)
|
||||
{
|
||||
_main_rotor.set_rotor_rpm(rotor_rpm);
|
||||
}
|
||||
|
@ -61,7 +61,7 @@ public:
|
||||
void set_desired_rotor_speed(float desired_speed) override;
|
||||
|
||||
// set_rpm - for rotor speed governor
|
||||
void set_rpm(int16_t rotor_rpm) override;
|
||||
void set_rpm(float rotor_rpm) override;
|
||||
|
||||
// get_main_rotor_speed - estimated rotor speed when no speed sensor or governor is used
|
||||
float get_main_rotor_speed() const override { return _main_rotor.get_rotor_speed(); }
|
||||
|
Loading…
Reference in New Issue
Block a user