AP_MotorsHeli: Set range of new RSC Servo object.
This commit is contained in:
parent
990761a13b
commit
91c7663ca2
@ -21,6 +21,13 @@
|
|||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
|
// init_servo - servo initialization on start-up
|
||||||
|
void AP_MotorsHeli_RSC::init_servo()
|
||||||
|
{
|
||||||
|
// set servo range
|
||||||
|
_servo_output.set_range(0,1000);
|
||||||
|
}
|
||||||
|
|
||||||
// recalc_scalers - recalculates various scalers used. Should be called at about 1hz to allow users to see effect of changing parameters
|
// recalc_scalers - recalculates various scalers used. Should be called at about 1hz to allow users to see effect of changing parameters
|
||||||
void AP_MotorsHeli_RSC::recalc_scalers()
|
void AP_MotorsHeli_RSC::recalc_scalers()
|
||||||
{
|
{
|
||||||
|
@ -22,6 +22,9 @@ public:
|
|||||||
_loop_rate(loop_rate)
|
_loop_rate(loop_rate)
|
||||||
{};
|
{};
|
||||||
|
|
||||||
|
// init_servo - servo initialization on start-up
|
||||||
|
void init_servo();
|
||||||
|
|
||||||
// set_critical_speed
|
// set_critical_speed
|
||||||
void set_critical_speed(int16_t critical_speed) { _critical_speed = critical_speed; }
|
void set_critical_speed(int16_t critical_speed) { _critical_speed = critical_speed; }
|
||||||
|
|
||||||
|
@ -367,6 +367,10 @@ void AP_MotorsHeli_Single::init_servos()
|
|||||||
init_swash_servo (_swash_servo_3);
|
init_swash_servo (_swash_servo_3);
|
||||||
|
|
||||||
_yaw_servo.set_angle(4500);
|
_yaw_servo.set_angle(4500);
|
||||||
|
|
||||||
|
// set main rotor servo range
|
||||||
|
// tail rotor servo use range as set in vehicle code for rc7
|
||||||
|
_main_rotor.init_servo();
|
||||||
}
|
}
|
||||||
|
|
||||||
// calculate_roll_pitch_collective_factors - calculate factors based on swash type and servo position
|
// calculate_roll_pitch_collective_factors - calculate factors based on swash type and servo position
|
||||||
|
Loading…
Reference in New Issue
Block a user