mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
AP_Motors: Heli eliminate _dt member and fix rsc_runup calculation
This commit is contained in:
parent
bc23ea4633
commit
65ca09600c
@ -372,7 +372,7 @@ void AP_MotorsHeli::recalc_scalers()
|
|||||||
if (_rsc_ramp_time <= 0) {
|
if (_rsc_ramp_time <= 0) {
|
||||||
_rsc_ramp_time = 1;
|
_rsc_ramp_time = 1;
|
||||||
}
|
}
|
||||||
_rsc_ramp_increment = 1000.0f / (_rsc_ramp_time / _dt);
|
_rsc_ramp_increment = 1000.0f / (_rsc_ramp_time * _loop_rate);
|
||||||
|
|
||||||
// recalculate rotor runup increment
|
// recalculate rotor runup increment
|
||||||
if (_rsc_runup_time <= 0 ) {
|
if (_rsc_runup_time <= 0 ) {
|
||||||
@ -381,7 +381,7 @@ void AP_MotorsHeli::recalc_scalers()
|
|||||||
if (_rsc_runup_time < _rsc_ramp_time) {
|
if (_rsc_runup_time < _rsc_ramp_time) {
|
||||||
_rsc_runup_time = _rsc_ramp_time;
|
_rsc_runup_time = _rsc_ramp_time;
|
||||||
}
|
}
|
||||||
_rsc_runup_increment = 1000.0f / (_rsc_runup_time * 100.0f);
|
_rsc_runup_increment = 1000.0f / (_rsc_runup_time * _loop_rate);
|
||||||
}
|
}
|
||||||
|
|
||||||
// get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
|
// get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
|
||||||
|
@ -116,7 +116,6 @@ public:
|
|||||||
_rsc_runup_increment(0.0f),
|
_rsc_runup_increment(0.0f),
|
||||||
_rotor_speed_estimate(0.0f),
|
_rotor_speed_estimate(0.0f),
|
||||||
_tail_direct_drive_out(0),
|
_tail_direct_drive_out(0),
|
||||||
_dt(0.01f),
|
|
||||||
_delta_phase_angle(0)
|
_delta_phase_angle(0)
|
||||||
{
|
{
|
||||||
AP_Param::setup_object_defaults(this, var_info);
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
@ -192,9 +191,6 @@ public:
|
|||||||
// var_info for holding Parameter information
|
// var_info for holding Parameter information
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
// set_dt for setting main loop rate time
|
|
||||||
void set_dt(float dt) { _dt = dt; }
|
|
||||||
|
|
||||||
// set_delta_phase_angle for setting variable phase angle compensation and force
|
// set_delta_phase_angle for setting variable phase angle compensation and force
|
||||||
// recalculation of collective factors
|
// recalculation of collective factors
|
||||||
void set_delta_phase_angle(int16_t angle);
|
void set_delta_phase_angle(int16_t angle);
|
||||||
|
Loading…
Reference in New Issue
Block a user