mirror of https://github.com/ArduPilot/ardupilot
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1373 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
d7c6bc7c16
commit
d95e8539d9
|
@ -15,7 +15,7 @@
|
||||||
// These are all experimental and underwork, jp 23-12-10
|
// These are all experimental and underwork, jp 23-12-10
|
||||||
//#define ENABLE_EXTRAS ENABLED
|
//#define ENABLE_EXTRAS ENABLED
|
||||||
//#define ENABLE_EXTRAINIT ENABLED
|
//#define ENABLE_EXTRAINIT ENABLED
|
||||||
//#define ENABLE_CAM ENABLED
|
#define ENABLE_CAM ENABLED
|
||||||
//#define ENABLE_AM ENABLED
|
//#define ENABLE_AM ENABLED
|
||||||
//#define ENABLE_xx ENABLED
|
//#define ENABLE_xx ENABLED
|
||||||
|
|
||||||
|
|
|
@ -75,8 +75,10 @@ AP_GPS_NONE GPS(NULL);
|
||||||
# error Must define GPS_PROTOCOL in your configuration file.
|
# error Must define GPS_PROTOCOL in your configuration file.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
AP_IMU imu(&adc, EE_IMU_OFFSET);
|
AP_IMU_Oilpan imu(&adc, EE_IMU_OFFSET);
|
||||||
AP_DCM dcm(&imu, &GPS);
|
AP_DCM dcm(&imu, &GPS);
|
||||||
|
|
||||||
|
//AP_DCM dcm(&imu, &gps, &compass);
|
||||||
|
|
||||||
|
|
||||||
// GENERAL VARIABLE DECLARATIONS
|
// GENERAL VARIABLE DECLARATIONS
|
||||||
|
|
|
@ -1,9 +1,9 @@
|
||||||
void init_camera()
|
void init_camera()
|
||||||
{
|
{
|
||||||
rc_camera_pitch.set_angle(4500);
|
rc_camera_pitch.set_angle(4500);
|
||||||
rc_camera_pitch.radio_min = 1000;
|
rc_camera_pitch.radio_min = rc_6.radio_min;
|
||||||
rc_camera_pitch.radio_trim = 1500;
|
rc_camera_pitch.radio_trim = rc_6.radio_trim;
|
||||||
rc_camera_pitch.radio_max = 2000;
|
rc_camera_pitch.radio_max = rc_6.radio_max;
|
||||||
|
|
||||||
rc_camera_yaw.set_angle(4500);
|
rc_camera_yaw.set_angle(4500);
|
||||||
rc_camera_yaw.radio_min = 1000;
|
rc_camera_yaw.radio_min = 1000;
|
||||||
|
@ -14,16 +14,14 @@ void init_camera()
|
||||||
void
|
void
|
||||||
camera_stabilization()
|
camera_stabilization()
|
||||||
{
|
{
|
||||||
|
rc_camera_pitch.set_pwm(APM_RC.InputCh(CH_6)); // I'm using CH 6 input here.
|
||||||
|
rc_camera_pitch.servo_out = rc_camera_pitch.control_mix(pitch_sensor / 2);
|
||||||
|
rc_camera_pitch.calc_pwm();
|
||||||
|
APM_RC.OutputCh(CH_5,rc_camera_pitch.radio_out);
|
||||||
|
|
||||||
rc_camera_pitch.servo_out = pitch_sensor;
|
//If you want to do control mixing use this function.
|
||||||
//rc_camera_pitch.servo_out;
|
// set servo_out to the control input from radio
|
||||||
rc_camera_pitch.calc_pwm();
|
//rc_camera_yaw = rc_2.control_mix(pitch_sensor);
|
||||||
|
//rc_camera_yaw.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();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -283,7 +283,7 @@
|
||||||
// STABILZE Angle Control
|
// STABILZE Angle Control
|
||||||
//
|
//
|
||||||
#ifndef STABILIZE_ROLL_P
|
#ifndef STABILIZE_ROLL_P
|
||||||
# define STABILIZE_ROLL_P 0.7
|
# define STABILIZE_ROLL_P 0.6
|
||||||
#endif
|
#endif
|
||||||
#ifndef STABILIZE_ROLL_I
|
#ifndef STABILIZE_ROLL_I
|
||||||
# define STABILIZE_ROLL_I 0.00
|
# define STABILIZE_ROLL_I 0.00
|
||||||
|
@ -296,7 +296,7 @@
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef STABILIZE_PITCH_P
|
#ifndef STABILIZE_PITCH_P
|
||||||
# define STABILIZE_PITCH_P 0.7
|
# define STABILIZE_PITCH_P 0.6
|
||||||
#endif
|
#endif
|
||||||
#ifndef STABILIZE_PITCH_I
|
#ifndef STABILIZE_PITCH_I
|
||||||
# define STABILIZE_PITCH_I 0.0
|
# define STABILIZE_PITCH_I 0.0
|
||||||
|
|
|
@ -2,9 +2,9 @@ void init_rc_in()
|
||||||
{
|
{
|
||||||
read_EEPROM_radio(); // read Radio limits
|
read_EEPROM_radio(); // read Radio limits
|
||||||
rc_1.set_angle(4500);
|
rc_1.set_angle(4500);
|
||||||
rc_1.dead_zone = 50;
|
rc_1.dead_zone = 60;
|
||||||
rc_2.set_angle(4500);
|
rc_2.set_angle(4500);
|
||||||
rc_2.dead_zone = 50;
|
rc_2.dead_zone = 60;
|
||||||
rc_3.set_range(0,1000);
|
rc_3.set_range(0,1000);
|
||||||
rc_3.dead_zone = 20;
|
rc_3.dead_zone = 20;
|
||||||
rc_3.scale_output = .8;
|
rc_3.scale_output = .8;
|
||||||
|
@ -12,7 +12,14 @@ void init_rc_in()
|
||||||
rc_4.dead_zone = 500;
|
rc_4.dead_zone = 500;
|
||||||
rc_5.set_range(0,1000);
|
rc_5.set_range(0,1000);
|
||||||
rc_5.set_filter(false);
|
rc_5.set_filter(false);
|
||||||
|
|
||||||
|
// for kP values
|
||||||
rc_6.set_range(200,800);
|
rc_6.set_range(200,800);
|
||||||
|
|
||||||
|
// for camera angles
|
||||||
|
//rc_6.set_angle(4500);
|
||||||
|
//rc_6.dead_zone = 60;
|
||||||
|
|
||||||
rc_7.set_range(0,1000);
|
rc_7.set_range(0,1000);
|
||||||
rc_8.set_range(0,1000);
|
rc_8.set_range(0,1000);
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue