2011-03-19 07:20:11 -03:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
2011-03-08 08:20:48 -04:00
|
|
|
|
2011-07-30 17:42:54 -03:00
|
|
|
//#if CAMERA_STABILIZER == ENABLED
|
2011-05-31 02:29:06 -03:00
|
|
|
|
2011-07-17 07:32:00 -03:00
|
|
|
static void init_camera()
|
2010-12-27 19:03:53 -04:00
|
|
|
{
|
2011-02-17 03:27:57 -04:00
|
|
|
g.rc_camera_pitch.set_angle(4500);
|
2011-09-08 01:59:44 -03:00
|
|
|
g.rc_camera_pitch.radio_min = 1200;
|
2011-05-09 23:17:25 -03:00
|
|
|
g.rc_camera_pitch.radio_trim = 1500;
|
2011-09-08 01:59:44 -03:00
|
|
|
g.rc_camera_pitch.radio_max = 1900;
|
2011-09-08 02:01:49 -03:00
|
|
|
//g.rc_camera_pitch.set_reverse(1);
|
2011-09-08 01:59:44 -03:00
|
|
|
|
|
|
|
// ch 6 high right is down.
|
|
|
|
|
2011-05-09 23:17:25 -03:00
|
|
|
|
2011-02-17 03:27:57 -04:00
|
|
|
g.rc_camera_roll.set_angle(4500);
|
|
|
|
g.rc_camera_roll.radio_min = 1000;
|
|
|
|
g.rc_camera_roll.radio_trim = 1500;
|
|
|
|
g.rc_camera_roll.radio_max = 2000;
|
2011-07-30 17:42:54 -03:00
|
|
|
|
|
|
|
g.rc_camera_roll.set_type(RC_CHANNEL_ANGLE_RAW);
|
|
|
|
g.rc_camera_pitch.set_type(RC_CHANNEL_ANGLE_RAW);
|
2010-12-27 19:03:53 -04:00
|
|
|
}
|
|
|
|
|
2011-07-17 07:32:00 -03:00
|
|
|
static void
|
2010-12-27 19:03:53 -04:00
|
|
|
camera_stabilization()
|
|
|
|
{
|
2011-07-12 17:04:15 -03:00
|
|
|
// PITCH
|
|
|
|
// -----
|
2011-01-28 01:39:17 -04:00
|
|
|
// allow control mixing
|
2011-07-12 17:04:15 -03:00
|
|
|
g.rc_camera_pitch.set_pwm(APM_RC.InputCh(CH_6)); // I'm using CH 6 input here.
|
2011-09-08 02:01:49 -03:00
|
|
|
g.rc_camera_pitch.servo_out = g.rc_camera_pitch.control_mix(dcm.pitch_sensor);
|
2011-09-08 01:59:44 -03:00
|
|
|
// limit
|
|
|
|
g.rc_camera_pitch.servo_out = constrain(g.rc_camera_pitch.servo_out, -4500, 4500);
|
2011-01-28 01:39:17 -04:00
|
|
|
|
|
|
|
// dont allow control mixing
|
2011-07-12 17:04:15 -03:00
|
|
|
/*
|
|
|
|
g.rc_camera_pitch.servo_out = dcm.pitch_sensor * -1;
|
|
|
|
*/
|
2010-12-27 19:03:53 -04:00
|
|
|
|
2011-07-12 17:04:15 -03:00
|
|
|
|
|
|
|
// ROLL
|
|
|
|
// -----
|
|
|
|
// allow control mixing
|
|
|
|
/*
|
|
|
|
g.rc_camera_roll.set_pwm(APM_RC.InputCh(CH_6)); // I'm using CH 6 input here.
|
|
|
|
g.rc_camera_roll.servo_out = g.rc_camera_roll.control_mix(-dcm.roll_sensor);
|
|
|
|
*/
|
|
|
|
|
|
|
|
// dont allow control mixing
|
2011-09-08 01:59:44 -03:00
|
|
|
// limit
|
|
|
|
g.rc_camera_roll.servo_out = constrain(-dcm.roll_sensor, -4500, 4500);
|
2011-07-12 17:04:15 -03:00
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// Output
|
|
|
|
// ------
|
|
|
|
g.rc_camera_pitch.calc_pwm();
|
2011-02-17 03:27:57 -04:00
|
|
|
g.rc_camera_roll.calc_pwm();
|
2011-01-28 01:39:17 -04:00
|
|
|
|
2011-07-12 17:04:15 -03:00
|
|
|
APM_RC.OutputCh(CH_5, g.rc_camera_pitch.radio_out);
|
|
|
|
APM_RC.OutputCh(CH_6, g.rc_camera_roll.radio_out);
|
2011-07-30 17:42:54 -03:00
|
|
|
//Serial.printf("c:%d\n", g.rc_camera_pitch.radio_out);
|
2010-12-27 19:03:53 -04:00
|
|
|
}
|
|
|
|
|
2011-07-30 17:42:54 -03:00
|
|
|
//#endif
|