mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 17:38:32 -04:00
AP_MotorsHeli: run RSC Control function in Output Min function
Move Output_Min() function into Heli_Single class as it will eventually be overloaded by other helicopter class types.
This commit is contained in:
parent
6cfdce1280
commit
b1c7ec9aac
@ -178,19 +178,6 @@ void AP_MotorsHeli::output()
|
|||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
// output_min - sets servos to neutral point
|
|
||||||
void AP_MotorsHeli::output_min()
|
|
||||||
{
|
|
||||||
// move swash to mid
|
|
||||||
move_swash(0,0,500,0);
|
|
||||||
|
|
||||||
// override limits flags
|
|
||||||
limit.roll_pitch = true;
|
|
||||||
limit.yaw = true;
|
|
||||||
limit.throttle_lower = true;
|
|
||||||
limit.throttle_upper = false;
|
|
||||||
}
|
|
||||||
|
|
||||||
// parameter_check - check if helicopter specific parameters are sensible
|
// parameter_check - check if helicopter specific parameters are sensible
|
||||||
bool AP_MotorsHeli::parameter_check() const
|
bool AP_MotorsHeli::parameter_check() const
|
||||||
{
|
{
|
||||||
|
@ -88,7 +88,7 @@ public:
|
|||||||
virtual void enable() = 0;
|
virtual void enable() = 0;
|
||||||
|
|
||||||
// output_min - sets servos to neutral point
|
// output_min - sets servos to neutral point
|
||||||
void output_min();
|
virtual void output_min() = 0;
|
||||||
|
|
||||||
// output_test - spin a motor at the pwm value specified
|
// output_test - spin a motor at the pwm value specified
|
||||||
// motor_seq is the motor's sequence number from 1 to the number of motors on the frame
|
// motor_seq is the motor's sequence number from 1 to the number of motors on the frame
|
||||||
|
@ -250,6 +250,22 @@ uint16_t AP_MotorsHeli_Single::get_motor_mask()
|
|||||||
return (1U << 0 | 1U << 1 | 1U << 2 | 1U << 3 | 1U << AP_MOTORS_HELI_SINGLE_AUX | 1U << AP_MOTORS_HELI_SINGLE_RSC);
|
return (1U << 0 | 1U << 1 | 1U << 2 | 1U << 3 | 1U << AP_MOTORS_HELI_SINGLE_AUX | 1U << AP_MOTORS_HELI_SINGLE_RSC);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// output_min - sets servos to neutral point
|
||||||
|
void AP_MotorsHeli_Single::output_min()
|
||||||
|
{
|
||||||
|
// move swash to mid
|
||||||
|
move_swash(0,0,500,0);
|
||||||
|
|
||||||
|
_main_rotor.output(ROTOR_CONTROL_STOP);
|
||||||
|
_tail_rotor.output(ROTOR_CONTROL_STOP);
|
||||||
|
|
||||||
|
// override limits flags
|
||||||
|
limit.roll_pitch = true;
|
||||||
|
limit.yaw = true;
|
||||||
|
limit.throttle_lower = true;
|
||||||
|
limit.throttle_upper = false;
|
||||||
|
}
|
||||||
|
|
||||||
// sends commands to the motors
|
// sends commands to the motors
|
||||||
void AP_MotorsHeli_Single::output_armed_stabilizing()
|
void AP_MotorsHeli_Single::output_armed_stabilizing()
|
||||||
{
|
{
|
||||||
|
@ -81,6 +81,9 @@ public:
|
|||||||
// pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
|
// pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
|
||||||
void output_test(uint8_t motor_seq, int16_t pwm);
|
void output_test(uint8_t motor_seq, int16_t pwm);
|
||||||
|
|
||||||
|
// output_min - sets servos to neutral point
|
||||||
|
void output_min();
|
||||||
|
|
||||||
// allow_arming - returns true if main rotor is spinning and it is ok to arm
|
// allow_arming - returns true if main rotor is spinning and it is ok to arm
|
||||||
bool allow_arming() const;
|
bool allow_arming() const;
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user