mirror of https://github.com/ArduPilot/ardupilot
upped the camera behavior for Max
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1569 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
aa6b1d0cd2
commit
40ec5d906d
|
@ -127,7 +127,7 @@ RC_Channel rc_7(EE_RADIO_7);
|
|||
RC_Channel rc_8(EE_RADIO_8);
|
||||
|
||||
RC_Channel rc_camera_pitch(EE_RADIO_9);
|
||||
RC_Channel rc_camera_yaw(EE_RADIO_10);
|
||||
RC_Channel rc_camera_roll(EE_RADIO_10);
|
||||
|
||||
int motor_out[4];
|
||||
byte flight_mode_channel;
|
||||
|
|
|
@ -5,23 +5,35 @@ void init_camera()
|
|||
rc_camera_pitch.radio_trim = rc_6.radio_trim;
|
||||
rc_camera_pitch.radio_max = rc_6.radio_max;
|
||||
|
||||
rc_camera_yaw.set_angle(4500);
|
||||
rc_camera_yaw.radio_min = 1000;
|
||||
rc_camera_yaw.radio_trim = 1500;
|
||||
rc_camera_yaw.radio_max = 2000;
|
||||
rc_camera_roll.set_angle(4500);
|
||||
rc_camera_roll.radio_min = 1000;
|
||||
rc_camera_roll.radio_trim = 1500;
|
||||
rc_camera_roll.radio_max = 2000;
|
||||
}
|
||||
|
||||
void
|
||||
camera_stabilization()
|
||||
{
|
||||
rc_camera_pitch.set_pwm(APM_RC.InputCh(CH_6)); // I'm using CH 6 input here.
|
||||
|
||||
// allow control mixing
|
||||
rc_camera_pitch.servo_out = rc_camera_pitch.control_mix(dcm.pitch_sensor / 2);
|
||||
|
||||
// dont allow control mixing
|
||||
//rc_camera_pitch.servo_out = dcm.pitch_sensor / 2;
|
||||
|
||||
rc_camera_pitch.calc_pwm();
|
||||
APM_RC.OutputCh(CH_5, rc_camera_pitch.radio_out);
|
||||
|
||||
|
||||
rc_camera_roll.servo_out = dcm.roll_sensor * 1;
|
||||
rc_camera_roll.calc_pwm();
|
||||
APM_RC.OutputCh(CH_6, rc_camera_pitch.radio_out);
|
||||
|
||||
|
||||
//If you want to do control mixing use this function.
|
||||
// set servo_out to the control input from radio
|
||||
//rc_camera_yaw = rc_2.control_mix(dcm.pitch_sensor);
|
||||
//rc_camera_yaw.calc_pwm();
|
||||
//rc_camera_roll = rc_2.control_mix(dcm.pitch_sensor);
|
||||
//rc_camera_roll.calc_pwm();
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue