mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-06 16:08:28 -04:00
8847a8c698
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1308 f9c3cf11-9bcb-44bc-f272-b75c42450872
30 lines
690 B
Plaintext
30 lines
690 B
Plaintext
void init_camera()
|
|
{
|
|
rc_camera_pitch.set_angle(4500);
|
|
rc_camera_pitch.radio_min = 1000;
|
|
rc_camera_pitch.radio_trim = 1500;
|
|
rc_camera_pitch.radio_max = 2000;
|
|
|
|
rc_camera_yaw.set_angle(4500);
|
|
rc_camera_yaw.radio_min = 1000;
|
|
rc_camera_yaw.radio_trim = 1500;
|
|
rc_camera_yaw.radio_max = 2000;
|
|
}
|
|
|
|
void
|
|
camera_stabilization()
|
|
{
|
|
|
|
rc_camera_pitch.servo_out = pitch_sensor;
|
|
//rc_camera_pitch.servo_out;
|
|
rc_camera_pitch.calc_pwm();
|
|
|
|
APM_RC.OutputCh(CH_5,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(pitch_sensor);
|
|
//rc_camera_yaw.calc_pwm();
|
|
}
|
|
|