mirror of https://github.com/ArduPilot/ardupilot
Camera stabilization updates
git-svn-id: https://arducopter.googlecode.com/svn/trunk@2239 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
a7b597bd0a
commit
d843f32a21
|
@ -3,9 +3,10 @@
|
|||
void init_camera()
|
||||
{
|
||||
g.rc_camera_pitch.set_angle(4500);
|
||||
g.rc_camera_pitch.radio_min = g.rc_6.radio_min;
|
||||
g.rc_camera_pitch.radio_trim = g.rc_6.radio_trim;
|
||||
g.rc_camera_pitch.radio_max = g.rc_6.radio_max;
|
||||
g.rc_camera_pitch.radio_min = 1000;
|
||||
g.rc_camera_pitch.radio_trim = 1500;
|
||||
g.rc_camera_pitch.radio_max = 2000;
|
||||
|
||||
|
||||
g.rc_camera_roll.set_angle(4500);
|
||||
g.rc_camera_roll.radio_min = 1000;
|
||||
|
@ -19,14 +20,14 @@ camera_stabilization()
|
|||
g.rc_camera_pitch.set_pwm(APM_RC.InputCh(CH_6)); // I'm using CH 6 input here.
|
||||
|
||||
// allow control mixing
|
||||
//g.rc_camera_pitch.servo_out = g.rc_camera_pitch.control_mix(dcm.pitch_sensor / 2);
|
||||
g.rc_camera_pitch.servo_out = g.rc_camera_pitch.control_mix(-dcm.pitch_sensor);
|
||||
|
||||
// dont allow control mixing
|
||||
g.rc_camera_pitch.servo_out = dcm.pitch_sensor / 2;
|
||||
//g.rc_camera_pitch.servo_out = dcm.pitch_sensor * -1;
|
||||
g.rc_camera_pitch.calc_pwm();
|
||||
APM_RC.OutputCh(CH_5, g.rc_camera_pitch.radio_out);
|
||||
|
||||
g.rc_camera_roll.servo_out = dcm.roll_sensor;
|
||||
g.rc_camera_roll.servo_out = -dcm.roll_sensor;
|
||||
g.rc_camera_roll.calc_pwm();
|
||||
APM_RC.OutputCh(CH_6, g.rc_camera_roll.radio_out);
|
||||
|
||||
|
|
Loading…
Reference in New Issue