Added camera reversing parameters in AP_Var
Added RTL Throttle Hold set/check
Added dynamic speed control to slow down as you reach waypoints and RTL Home
upped Yaw Dead zone slightly.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@2841 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jasonshort 2011-07-12 20:04:15 +00:00
parent 0412dbac79
commit 6d3bccf85a
6 changed files with 57 additions and 24 deletions

View File

@ -259,6 +259,7 @@ const char* flight_mode_strings[] = {
// Radio
// -----
byte control_mode = STABILIZE;
byte old_control_mode = STABILIZE;
byte oldSwitchPosition; // for remembering the control mode switch
int motor_out[8];

View File

@ -8,34 +8,51 @@ void init_camera()
g.rc_camera_pitch.radio_min = 1000;
g.rc_camera_pitch.radio_trim = 1500;
g.rc_camera_pitch.radio_max = 2000;
g.rc_camera_pitch.set_reverse(g.cam_pitch_reverse);
g.rc_camera_roll.set_angle(4500);
g.rc_camera_roll.radio_min = 1000;
g.rc_camera_roll.radio_trim = 1500;
g.rc_camera_roll.radio_max = 2000;
g.rc_camera_roll.set_reverse(g.cam_roll_reverse);
}
void
camera_stabilization()
{
g.rc_camera_pitch.set_pwm(APM_RC.InputCh(CH_6)); // I'm using CH 6 input here.
// PITCH
// -----
// allow control mixing
g.rc_camera_pitch.set_pwm(APM_RC.InputCh(CH_6)); // I'm using CH 6 input here.
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 * -1;
g.rc_camera_pitch.calc_pwm();
APM_RC.OutputCh(CH_5, g.rc_camera_pitch.radio_out);
/*
g.rc_camera_pitch.servo_out = dcm.pitch_sensor * -1;
*/
// ROLL
// -----
// allow control mixing
/*
g.rc_camera_roll.set_pwm(APM_RC.InputCh(CH_6)); // I'm using CH 6 input here.
g.rc_camera_roll.servo_out = g.rc_camera_roll.control_mix(-dcm.roll_sensor);
*/
// dont allow control mixing
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);
//If you want to do control mixing use this function.
// set servo_out to the control input from radio
//rc_camera_roll = g.rc_2.control_mix(dcm.pitch_sensor);
//rc_camera_roll.calc_pwm();
// Output
// ------
g.rc_camera_pitch.calc_pwm();
g.rc_camera_roll.calc_pwm();
APM_RC.OutputCh(CH_5, g.rc_camera_pitch.radio_out);
APM_RC.OutputCh(CH_6, g.rc_camera_roll.radio_out);
}
#endif

View File

@ -104,6 +104,9 @@ public:
k_param_throttle_cruise,
k_param_flight_modes,
k_param_esc_calibrate,
k_param_cam_pitch_reverse,
k_param_cam_roll_reverse,
#if FRAME_CONFIG == HELI_FRAME
//
@ -239,6 +242,9 @@ public:
RC_Channel rc_camera_pitch;
RC_Channel rc_camera_roll;
AP_Int8 cam_pitch_reverse;
AP_Int8 cam_roll_reverse;
// PID controllers
PID pid_rate_roll;
PID pid_rate_pitch;
@ -327,6 +333,10 @@ public:
rc_camera_pitch (k_param_rc_9, NULL),
rc_camera_roll (k_param_rc_10, NULL),
cam_pitch_reverse (0, k_param_cam_pitch_reverse, PSTR("CAM_P_REV")),
cam_roll_reverse (0, k_param_cam_roll_reverse, PSTR("CAM_R_REV")),
// PID controller group key name initial P initial I initial D initial imax
//--------------------------------------------------------------------------------------------------------------------------------------------------------------------
pid_rate_roll (k_param_pid_rate_roll, PSTR("RATE_RLL_"), RATE_ROLL_P, RATE_ROLL_I, 0, RATE_ROLL_IMAX * 100),

View File

@ -144,12 +144,12 @@ void calc_rate_nav()
int groundspeed = (float)g_gps->ground_speed * cos(radians((float)target_error/100));
// Reduce speed on RTL
if(control_mode == RTL){
waypoint_speed = min((wp_distance * 100), 600);
waypoint_speed = max(g.waypoint_speed_max.get(), 30);
}else{
waypoint_speed = g.waypoint_speed_max.get();
}
//if(control_mode == RTL){
waypoint_speed = min((wp_distance * 100), g.waypoint_speed_max.get());
waypoint_speed = max(waypoint_speed, 80);
//}else{
// waypoint_speed = g.waypoint_speed_max.get();
//}
int error = constrain(waypoint_speed - groundspeed, -1000, 1000);
// Scale response by kP

View File

@ -14,6 +14,10 @@ void init_rc_in()
g.rc_3.scale_output = .9;
g.rc_4.set_angle(4500);
// reverse: CW = left
// normal: CW = left???
g.rc_1.set_type(RC_CHANNEL_ANGLE_RAW);
g.rc_2.set_type(RC_CHANNEL_ANGLE_RAW);
g.rc_4.set_type(RC_CHANNEL_ANGLE_RAW);
@ -22,7 +26,7 @@ void init_rc_in()
g.rc_1.dead_zone = 60; // 60 = .6 degrees
g.rc_2.dead_zone = 60;
g.rc_3.dead_zone = 60;
g.rc_4.dead_zone = 500;// 0 = hybrid rate approach
g.rc_4.dead_zone = 600;// 0 = hybrid rate approach
//set auxiliary ranges
g.rc_5.set_range(0,1000);

View File

@ -40,7 +40,7 @@ const struct Menu::command main_menu_commands[] PROGMEM = {
};
// Create the top-level menu object.
MENU(main_menu, "AC 2.0.34 Beta", main_menu_commands);
MENU(main_menu, "AC 2.0.35 Beta", main_menu_commands);
void init_ardupilot()
{
@ -350,6 +350,7 @@ void set_mode(byte mode)
// don't switch modes if we are already in the correct mode.
return;
}
old_control_mode = control_mode;
control_mode = mode;
control_mode = constrain(control_mode, 0, NUM_MODES - 1);
@ -394,11 +395,12 @@ void set_mode(byte mode)
break;
case GUIDED:
init_throttle_cruise();
set_next_WP(&guided_WP);
break;
case RTL:
//init_throttle_cruise();
init_throttle_cruise();
do_RTL();
break;
@ -479,11 +481,10 @@ init_simple_bearing()
void
init_throttle_cruise()
{
//if(set_throttle_cruise_flag == false){
if(g.rc_3.control_in > 200){
g.throttle_cruise.set_and_save(g.rc_3.control_in);
}
//}
// are we moving from manual throttle to auto_throttle?
if((old_control_mode <= SIMPLE) && (g.rc_3.control_in > 150)){
g.throttle_cruise.set_and_save(g.rc_3.control_in);
}
}
#if BROKEN_SLIDER == 1