mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
ACM: Precision Loiter RePositioning code.
Protected behind a #define
This commit is contained in:
parent
323d7fac43
commit
f48ec39cfa
@ -69,3 +69,6 @@
|
||||
|
||||
//#define LOGGING_ENABLED DISABLED
|
||||
|
||||
#define LOITER_REPOSITIONING DISABLED // Experimental Do Not Use
|
||||
// #define LOITER_RP ROLL_PITCH_LOITER_PR
|
||||
|
||||
|
@ -1598,6 +1598,7 @@ bool set_roll_pitch_mode(uint8_t new_roll_pitch_mode)
|
||||
case ROLL_PITCH_AUTO:
|
||||
case ROLL_PITCH_STABLE_OF:
|
||||
case ROLL_PITCH_TOY:
|
||||
case ROLL_PITCH_LOITER_PR:
|
||||
roll_pitch_initialised = true;
|
||||
break;
|
||||
}
|
||||
@ -1704,6 +1705,17 @@ void update_roll_pitch_mode(void)
|
||||
case ROLL_PITCH_TOY:
|
||||
roll_pitch_toy();
|
||||
break;
|
||||
|
||||
case ROLL_PITCH_LOITER_PR:
|
||||
|
||||
// LOITER does not get SIMPLE mode ability
|
||||
|
||||
nav_roll += constrain(wrap_180(auto_roll - nav_roll), -g.auto_slew_rate.get(), g.auto_slew_rate.get()); // 40 deg a second
|
||||
nav_pitch += constrain(wrap_180(auto_pitch - nav_pitch), -g.auto_slew_rate.get(), g.auto_slew_rate.get()); // 40 deg a second
|
||||
|
||||
get_stabilize_roll(nav_roll);
|
||||
get_stabilize_pitch(nav_pitch);
|
||||
break;
|
||||
}
|
||||
|
||||
#if FRAME_CONFIG != HELI_FRAME
|
||||
|
@ -813,6 +813,10 @@
|
||||
#ifndef LOITER_IMAX
|
||||
# define LOITER_IMAX 30 // degrees
|
||||
#endif
|
||||
#ifndef LOITER_REPOSITION_RATE
|
||||
# define LOITER_REPOSITION_RATE 500.0 // cm/s
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Loiter Navigation control gains
|
||||
|
@ -27,8 +27,8 @@
|
||||
#define ROLL_PITCH_ACRO 1
|
||||
#define ROLL_PITCH_AUTO 2
|
||||
#define ROLL_PITCH_STABLE_OF 3
|
||||
#define ROLL_PITCH_TOY 4 // THOR This is the Roll and Pitch
|
||||
// mode
|
||||
#define ROLL_PITCH_TOY 4 // THOR This is the Roll and Pitch mode
|
||||
#define ROLL_PITCH_LOITER_PR 5
|
||||
|
||||
#define THROTTLE_MANUAL 0 // manual throttle mode - pilot input goes directly to motors
|
||||
#define THROTTLE_MANUAL_TILT_COMPENSATED 1 // mostly manual throttle but with some tilt compensation
|
||||
|
@ -198,6 +198,36 @@ static void run_navigation_contollers()
|
||||
update_nav_wp();
|
||||
break;
|
||||
|
||||
#if LOITER_REPOSITIONING == ENABLED // Robert Lefebvre 16/12/2012
|
||||
// switch passthrough to LOITER
|
||||
case LOITER:
|
||||
case POSITION:
|
||||
// This feature allows us to reposition the quad when the user lets
|
||||
// go of the sticks
|
||||
|
||||
if((abs(g.rc_2.control_in) + abs(g.rc_1.control_in)) > 100) {
|
||||
ap.loiter_override = true;
|
||||
}
|
||||
|
||||
// Allow the user to take control temporarily,
|
||||
if(ap.loiter_override){
|
||||
|
||||
// reset LOITER to current position
|
||||
next_WP.lat += LOITER_REPOSITION_RATE * dTnav * ((sin_yaw_y * g.rc_1.control_in) + (cos_yaw_x * g.rc_2.control_in))/4500.0;
|
||||
next_WP.lng += LOITER_REPOSITION_RATE * dTnav * ((sin_yaw_y * g.rc_2.control_in) + (cos_yaw_x * g.rc_1.control_in))/4500.0;
|
||||
|
||||
if((abs(g.rc_2.control_in) + abs(g.rc_1.control_in)) < 100) {
|
||||
next_WP.lat = current_loc.lat;
|
||||
next_WP.lng = current_loc.lng;
|
||||
ap.loiter_override = false;
|
||||
}
|
||||
}
|
||||
wp_control = LOITER_MODE;
|
||||
// calculates the desired Roll and Pitch
|
||||
update_nav_wp();
|
||||
break;
|
||||
#else // LOITER_REPOSITIONING
|
||||
|
||||
// switch passthrough to LOITER
|
||||
case LOITER:
|
||||
case POSITION:
|
||||
@ -230,6 +260,7 @@ static void run_navigation_contollers()
|
||||
// calculates the desired Roll and Pitch
|
||||
update_nav_wp();
|
||||
break;
|
||||
#endif // LOITER_REPOSITIONING
|
||||
|
||||
case LAND:
|
||||
verify_land();
|
||||
@ -256,7 +287,6 @@ static void run_navigation_contollers()
|
||||
if(home_distance > SUPER_SIMPLE_RADIUS) { // 10m from home
|
||||
// we reset the angular offset to be a vector from home to the quad
|
||||
initial_simple_bearing = wrap_360(home_bearing+18000);
|
||||
//cliSerial->printf("ISB: %d\n", initial_simple_bearing);
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -347,6 +377,88 @@ static bool check_missed_wp()
|
||||
|
||||
#define NAV_ERR_MAX 600
|
||||
#define NAV_RATE_ERR_MAX 250
|
||||
|
||||
#if LOITER_REPOSITIONING == ENABLED // Robert Lefebvre 16/12/2012
|
||||
|
||||
static void calc_loiter(int16_t x_error, int16_t y_error)
|
||||
{
|
||||
int32_t p,i,d; // used to capture pid values for logging
|
||||
int32_t output;
|
||||
int32_t x_target_speed, y_target_speed;
|
||||
|
||||
// East / West
|
||||
x_target_speed = g.pi_loiter_lon.get_p(x_error); // calculate desired speed from lon error
|
||||
|
||||
#if LOGGING_ENABLED == ENABLED
|
||||
// log output if PID logging is on and we are tuning the yaw
|
||||
if( g.log_bitmask & MASK_LOG_PID && (g.radio_tuning == CH6_LOITER_KP || g.radio_tuning == CH6_LOITER_KI) ) {
|
||||
Log_Write_PID(CH6_LOITER_KP, x_error, x_target_speed, 0, 0, x_target_speed, tuning_value);
|
||||
}
|
||||
#endif
|
||||
|
||||
// calculate rate error
|
||||
x_rate_error = x_target_speed - lon_speed; // calc the speed error
|
||||
|
||||
p = g.pid_loiter_rate_lon.get_p(x_rate_error);
|
||||
i = g.pid_loiter_rate_lon.get_i(x_rate_error, dTnav);
|
||||
d = g.pid_loiter_rate_lon.get_d(x_rate_error, dTnav);
|
||||
d = constrain(d, -2000, 2000);
|
||||
|
||||
// get rid of noise
|
||||
if(abs(lon_speed) < 50) {
|
||||
d = 0;
|
||||
}
|
||||
|
||||
output = p + i + d;
|
||||
nav_lon = constrain(output, -32000, 32000); // constraint to remove chance of overflow when adding int32_t to int16_t
|
||||
|
||||
#if LOGGING_ENABLED == ENABLED
|
||||
// log output if PID logging is on and we are tuning the yaw
|
||||
if( g.log_bitmask & MASK_LOG_PID && (g.radio_tuning == CH6_LOITER_RATE_KP || g.radio_tuning == CH6_LOITER_RATE_KI || g.radio_tuning == CH6_LOITER_RATE_KD) ) {
|
||||
Log_Write_PID(CH6_LOITER_RATE_KP, x_rate_error, p, i, d, nav_lon, tuning_value);
|
||||
}
|
||||
#endif
|
||||
|
||||
// North / South
|
||||
y_target_speed = g.pi_loiter_lat.get_p(y_error); // calculate desired speed from lat error
|
||||
|
||||
#if LOGGING_ENABLED == ENABLED
|
||||
// log output if PID logging is on and we are tuning the yaw
|
||||
if( g.log_bitmask & MASK_LOG_PID && (g.radio_tuning == CH6_LOITER_KP || g.radio_tuning == CH6_LOITER_KI) ) {
|
||||
Log_Write_PID(CH6_LOITER_KP+100, y_error, y_target_speed, 0, 0, y_target_speed, tuning_value);
|
||||
}
|
||||
#endif
|
||||
|
||||
// calculate rate error
|
||||
y_rate_error = y_target_speed - lat_speed; // calc the speed error
|
||||
|
||||
p = g.pid_loiter_rate_lat.get_p(y_rate_error);
|
||||
i = g.pid_loiter_rate_lat.get_i(y_rate_error, dTnav);
|
||||
d = g.pid_loiter_rate_lat.get_d(y_rate_error, dTnav);
|
||||
d = constrain(d, -2000, 2000);
|
||||
|
||||
// get rid of noise
|
||||
if(abs(lat_speed) < 50) {
|
||||
d = 0;
|
||||
}
|
||||
|
||||
output = p + i + d;
|
||||
nav_lat = constrain(output, -32000, 32000); // constraint to remove chance of overflow when adding int32_t to int16_t
|
||||
|
||||
#if LOGGING_ENABLED == ENABLED
|
||||
// log output if PID logging is on and we are tuning the yaw
|
||||
if( g.log_bitmask & MASK_LOG_PID && (g.radio_tuning == CH6_LOITER_RATE_KP || g.radio_tuning == CH6_LOITER_RATE_KI || g.radio_tuning == CH6_LOITER_RATE_KD) ) {
|
||||
Log_Write_PID(CH6_LOITER_RATE_KP+100, y_rate_error, p, i, d, nav_lat, tuning_value);
|
||||
}
|
||||
#endif
|
||||
|
||||
// copy over I term to Nav_Rate
|
||||
g.pid_nav_lon.set_integrator(g.pid_loiter_rate_lon.get_integrator());
|
||||
g.pid_nav_lat.set_integrator(g.pid_loiter_rate_lat.get_integrator());
|
||||
}
|
||||
|
||||
#else // LOITER_REPOSITIONING
|
||||
|
||||
static void calc_loiter(int16_t x_error, int16_t y_error)
|
||||
{
|
||||
int32_t p,i,d; // used to capture pid values for logging
|
||||
@ -424,6 +536,8 @@ static void calc_loiter(int16_t x_error, int16_t y_error)
|
||||
g.pid_nav_lat.set_integrator(g.pid_loiter_rate_lat.get_integrator());
|
||||
}
|
||||
|
||||
#endif // LOITER_REPOSITIONING
|
||||
|
||||
static void calc_nav_rate(int16_t max_speed)
|
||||
{
|
||||
float temp, temp_x, temp_y;
|
||||
@ -476,7 +590,6 @@ static void calc_nav_rate(int16_t max_speed)
|
||||
// We use the DCM's matrix to precalculate these trig values at 50hz
|
||||
static void calc_nav_pitch_roll()
|
||||
{
|
||||
//cliSerial->printf("ys %ld, cx %1.4f, _cx %1.4f | sy %1.4f, _sy %1.4f\n", dcm.yaw_sensor, cos_yaw_x, _cos_yaw_x, sin_yaw_y, _sin_yaw_y);
|
||||
// rotate the vector
|
||||
auto_roll = (float)nav_lon * sin_yaw_y - (float)nav_lat * cos_yaw_x;
|
||||
auto_pitch = (float)nav_lon * cos_yaw_x + (float)nav_lat * sin_yaw_y;
|
||||
|
@ -489,7 +489,7 @@ static void set_mode(byte mode)
|
||||
ap.manual_throttle = true;
|
||||
ap.manual_attitude = false;
|
||||
set_yaw_mode(YAW_HOLD);
|
||||
set_roll_pitch_mode(ROLL_PITCH_AUTO);
|
||||
set_roll_pitch_mode(LOITER_RP);
|
||||
set_throttle_mode(THROTTLE_MANUAL);
|
||||
set_next_WP(¤t_loc);
|
||||
break;
|
||||
|
Loading…
Reference in New Issue
Block a user