2010-12-27 19:09:08 -04:00
|
|
|
void init_rc_in()
|
2010-12-19 12:40:33 -04:00
|
|
|
{
|
2010-12-27 21:45:43 -04:00
|
|
|
read_EEPROM_radio(); // read Radio limits
|
2010-12-19 12:40:33 -04:00
|
|
|
rc_1.set_angle(4500);
|
2011-01-26 03:14:54 -04:00
|
|
|
rc_1.dead_zone = 60; // 60 = .6 degrees
|
2010-12-19 12:40:33 -04:00
|
|
|
rc_2.set_angle(4500);
|
2011-01-26 03:14:54 -04:00
|
|
|
rc_2.dead_zone = 60;
|
2010-12-19 12:40:33 -04:00
|
|
|
rc_3.set_range(0,1000);
|
|
|
|
rc_3.dead_zone = 20;
|
2011-01-02 16:34:42 -04:00
|
|
|
rc_3.scale_output = .9;
|
2010-12-19 12:40:33 -04:00
|
|
|
rc_4.set_angle(6000);
|
|
|
|
rc_4.dead_zone = 500;
|
|
|
|
rc_5.set_range(0,1000);
|
|
|
|
rc_5.set_filter(false);
|
2010-12-30 03:40:57 -04:00
|
|
|
|
|
|
|
// for kP values
|
2011-01-02 16:34:42 -04:00
|
|
|
//rc_6.set_range(200,800);
|
|
|
|
rc_6.set_range(0,4000);
|
2010-12-30 03:40:57 -04:00
|
|
|
|
|
|
|
// for camera angles
|
|
|
|
//rc_6.set_angle(4500);
|
|
|
|
//rc_6.dead_zone = 60;
|
|
|
|
|
2010-12-19 12:40:33 -04:00
|
|
|
rc_7.set_range(0,1000);
|
|
|
|
rc_8.set_range(0,1000);
|
2010-12-27 19:09:08 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
void init_rc_out()
|
|
|
|
{
|
2010-12-19 12:40:33 -04:00
|
|
|
#if ARM_AT_STARTUP == 1
|
2010-12-27 19:09:08 -04:00
|
|
|
motor_armed = 1;
|
2010-12-19 12:40:33 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
APM_RC.OutputCh(CH_1, rc_3.radio_min); // Initialization of servo outputs
|
|
|
|
APM_RC.OutputCh(CH_2, rc_3.radio_min);
|
|
|
|
APM_RC.OutputCh(CH_3, rc_3.radio_min);
|
|
|
|
APM_RC.OutputCh(CH_4, rc_3.radio_min);
|
|
|
|
|
|
|
|
APM_RC.Init(); // APM Radio initialization
|
|
|
|
|
|
|
|
APM_RC.OutputCh(CH_1, rc_3.radio_min); // Initialization of servo outputs
|
|
|
|
APM_RC.OutputCh(CH_2, rc_3.radio_min);
|
|
|
|
APM_RC.OutputCh(CH_3, rc_3.radio_min);
|
|
|
|
APM_RC.OutputCh(CH_4, rc_3.radio_min);
|
|
|
|
}
|
|
|
|
|
|
|
|
void read_radio()
|
2010-12-26 01:25:52 -04:00
|
|
|
{
|
2010-12-19 12:40:33 -04:00
|
|
|
rc_1.set_pwm(APM_RC.InputCh(CH_1));
|
|
|
|
rc_2.set_pwm(APM_RC.InputCh(CH_2));
|
|
|
|
rc_3.set_pwm(APM_RC.InputCh(CH_3));
|
|
|
|
rc_4.set_pwm(APM_RC.InputCh(CH_4));
|
|
|
|
rc_5.set_pwm(APM_RC.InputCh(CH_5));
|
|
|
|
rc_6.set_pwm(APM_RC.InputCh(CH_6));
|
|
|
|
rc_7.set_pwm(APM_RC.InputCh(CH_7));
|
|
|
|
rc_8.set_pwm(APM_RC.InputCh(CH_8));
|
|
|
|
//Serial.printf_P(PSTR("OUT 1: %d\t2: %d\t3: %d\t4: %d \n"), rc_1.control_in, rc_2.control_in, rc_3.control_in, rc_4.control_in);
|
|
|
|
}
|
|
|
|
|
|
|
|
void trim_radio()
|
|
|
|
{
|
2010-12-27 21:45:43 -04:00
|
|
|
for (byte i = 0; i < 30; i++){
|
2010-12-26 01:25:52 -04:00
|
|
|
read_radio();
|
|
|
|
}
|
2010-12-19 12:40:33 -04:00
|
|
|
rc_1.trim(); // roll
|
|
|
|
rc_2.trim(); // pitch
|
|
|
|
rc_4.trim(); // yaw
|
|
|
|
}
|
|
|
|
|
2010-12-27 21:26:05 -04:00
|
|
|
void trim_yaw()
|
|
|
|
{
|
2010-12-27 21:45:43 -04:00
|
|
|
for (byte i = 0; i < 30; i++){
|
2010-12-27 21:26:05 -04:00
|
|
|
read_radio();
|
|
|
|
}
|
|
|
|
rc_4.trim(); // yaw
|
|
|
|
}
|