mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
ArduCopter: restored set_range calls for RC_Channels 5 ~ 8.
This commit is contained in:
parent
0dc0e3801c
commit
f137f51ec0
@ -38,7 +38,11 @@ static void init_rc_in()
|
|||||||
g.rc_4.set_type(RC_CHANNEL_ANGLE_RAW);
|
g.rc_4.set_type(RC_CHANNEL_ANGLE_RAW);
|
||||||
|
|
||||||
//set auxiliary ranges
|
//set auxiliary ranges
|
||||||
update_aux_servo_function(&g.rc_5, &g.rc_6, &g.rc_7, &g.rc_8);
|
g.rc_5.set_range(0,1000);
|
||||||
|
g.rc_6.set_range(0,1000);
|
||||||
|
g.rc_7.set_range(0,1000);
|
||||||
|
g.rc_8.set_range(0,1000);
|
||||||
|
update_aux_servo_function(&g.rc_camera_roll, &g.rc_camera_pitch, &g.rc_camera_yaw);
|
||||||
}
|
}
|
||||||
|
|
||||||
static void init_rc_out()
|
static void init_rc_out()
|
||||||
@ -54,7 +58,6 @@ static void init_rc_out()
|
|||||||
motors.set_min_throttle(g.throttle_min);
|
motors.set_min_throttle(g.throttle_min);
|
||||||
motors.set_max_throttle(g.throttle_max);
|
motors.set_max_throttle(g.throttle_max);
|
||||||
|
|
||||||
|
|
||||||
for(byte i = 0; i < 5; i++){
|
for(byte i = 0; i < 5; i++){
|
||||||
delay(20);
|
delay(20);
|
||||||
read_radio();
|
read_radio();
|
||||||
@ -63,8 +66,6 @@ static void init_rc_out()
|
|||||||
// we want the input to be scaled correctly
|
// we want the input to be scaled correctly
|
||||||
g.rc_3.set_range_out(0,1000);
|
g.rc_3.set_range_out(0,1000);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
// sanity check - prevent unconfigured radios from outputting
|
// sanity check - prevent unconfigured radios from outputting
|
||||||
if(g.rc_3.radio_min >= 1300){
|
if(g.rc_3.radio_min >= 1300){
|
||||||
g.rc_3.radio_min = g.rc_3.radio_in;
|
g.rc_3.radio_min = g.rc_3.radio_in;
|
||||||
@ -102,6 +103,7 @@ static void init_rc_out()
|
|||||||
|
|
||||||
void output_min()
|
void output_min()
|
||||||
{
|
{
|
||||||
|
// enable motors
|
||||||
motors.enable();
|
motors.enable();
|
||||||
motors.output_min();
|
motors.output_min();
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user