mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
Camera.pde: Implemented gyro based camera stabilization to support continuous servo gimbals.
This commit is contained in:
parent
278e215a21
commit
ddd069ad83
@ -18,18 +18,21 @@ static void init_camera()
|
||||
static void
|
||||
camera_stabilization()
|
||||
{
|
||||
int32_t p_sensor_value = g.camera_pitch_continuous ? (ahrs.get_gyro().y * 100) : ahrs.pitch_sensor;
|
||||
int32_t r_sensor_value = g.camera_roll_continuous ? (ahrs.get_gyro().x * 100) : ahrs.roll_sensor;
|
||||
|
||||
// PITCH
|
||||
// -----
|
||||
// Allow user to control camera pitch with channel 6 (mixed with pitch DCM)
|
||||
if(g.radio_tuning == 0) {
|
||||
g.rc_camera_pitch.set_pwm(g.rc_6.radio_in);
|
||||
g.rc_camera_pitch.servo_out = g.rc_camera_pitch.control_mix(ahrs.pitch_sensor);
|
||||
g.rc_camera_pitch.servo_out = g.rc_camera_pitch.control_mix(p_sensor_value);
|
||||
}else{
|
||||
// unless channel 6 is already being used for tuning
|
||||
g.rc_camera_pitch.servo_out = ahrs.pitch_sensor * -1;
|
||||
g.rc_camera_pitch.servo_out = p_sensor_value * -1;
|
||||
}
|
||||
g.rc_camera_pitch.servo_out = (float)g.rc_camera_pitch.servo_out * g.camera_pitch_gain;
|
||||
|
||||
|
||||
// limit
|
||||
//g.rc_camera_pitch.servo_out = constrain(g.rc_camera_pitch.servo_out, -4500, 4500);
|
||||
|
||||
@ -43,7 +46,7 @@ camera_stabilization()
|
||||
*/
|
||||
|
||||
// dont allow control mixing
|
||||
g.rc_camera_roll.servo_out = (float)-ahrs.roll_sensor * g.camera_roll_gain;
|
||||
g.rc_camera_roll.servo_out = (float)-r_sensor_value * g.camera_roll_gain;
|
||||
|
||||
// limit
|
||||
//g.rc_camera_roll.servo_out = constrain(-ahrs.roll_sensor, -4500, 4500);
|
||||
|
Loading…
Reference in New Issue
Block a user