Skip to content
Snippets Groups Projects

Compare revisions

Changes are shown as if the source revision was being merged into the target revision. Learn more about comparing revisions.

Source

Select target project
No results found

Target

Select target project
  • opensource/ardupilot
  • opensource/baitboat
2 results
Show changes
Commits on Source (16)
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#define THISFIRMWARE "ArduCopter V3.0.0-rc4" #define THISFIRMWARE "ArduCopter V3.0.0"
/* /*
* ArduCopter Version 3.0 * ArduCopter Version 3.0
* Creator: Jason Short * Creator: Jason Short
......
...@@ -122,15 +122,14 @@ get_roll_rate_stabilized_ef(int32_t stick_angle) ...@@ -122,15 +122,14 @@ get_roll_rate_stabilized_ef(int32_t stick_angle)
angle_error = constrain_int32(angle_error, -MAX_ROLL_OVERSHOOT, MAX_ROLL_OVERSHOOT); angle_error = constrain_int32(angle_error, -MAX_ROLL_OVERSHOOT, MAX_ROLL_OVERSHOOT);
} }
if (motors.armed() == false || ((g.rc_3.control_in == 0) && !ap.failsafe_radio)) { // reset target angle to current angle if motors not spinning
if (!motors.armed() || g.rc_3.servo_out == 0) {
angle_error = 0; angle_error = 0;
} }
// update roll_axis to be within max_angle_overshoot of our current heading // update roll_axis to be within max_angle_overshoot of our current heading
roll_axis = wrap_180_cd(angle_error + ahrs.roll_sensor); roll_axis = wrap_180_cd(angle_error + ahrs.roll_sensor);
// set earth frame targets for rate controller
// set earth frame targets for rate controller // set earth frame targets for rate controller
set_roll_rate_target(g.pi_stabilize_roll.get_p(angle_error) + target_rate, EARTH_FRAME); set_roll_rate_target(g.pi_stabilize_roll.get_p(angle_error) + target_rate, EARTH_FRAME);
} }
...@@ -158,7 +157,8 @@ get_pitch_rate_stabilized_ef(int32_t stick_angle) ...@@ -158,7 +157,8 @@ get_pitch_rate_stabilized_ef(int32_t stick_angle)
angle_error = constrain_int32(angle_error, -MAX_PITCH_OVERSHOOT, MAX_PITCH_OVERSHOOT); angle_error = constrain_int32(angle_error, -MAX_PITCH_OVERSHOOT, MAX_PITCH_OVERSHOOT);
} }
if (motors.armed() == false || ((g.rc_3.control_in == 0) && !ap.failsafe_radio)) { // reset target angle to current angle if motors not spinning
if (!motors.armed() || g.rc_3.servo_out == 0) {
angle_error = 0; angle_error = 0;
} }
...@@ -189,7 +189,8 @@ get_yaw_rate_stabilized_ef(int32_t stick_angle) ...@@ -189,7 +189,8 @@ get_yaw_rate_stabilized_ef(int32_t stick_angle)
// limit the maximum overshoot // limit the maximum overshoot
angle_error = constrain_int32(angle_error, -MAX_YAW_OVERSHOOT, MAX_YAW_OVERSHOOT); angle_error = constrain_int32(angle_error, -MAX_YAW_OVERSHOOT, MAX_YAW_OVERSHOOT);
if (motors.armed() == false || ((g.rc_3.control_in == 0) && !ap.failsafe_radio)) { // reset target angle to current heading if motors not spinning
if (!motors.armed() || g.rc_3.servo_out == 0) {
angle_error = 0; angle_error = 0;
} }
...@@ -1019,10 +1020,6 @@ get_throttle_rate(float z_target_speed) ...@@ -1019,10 +1020,6 @@ get_throttle_rate(float z_target_speed)
set_throttle_out(g.throttle_cruise+output, true); set_throttle_out(g.throttle_cruise+output, true);
} }
// limit loiter & waypoint navigation from causing too much lean
// To-Do: ensure that this limit is cleared when this throttle controller is not running so that loiter is not left constrained for Position mode
wp_nav.set_angle_limit(4500 - constrain_float((z_rate_error - 100) * 10, 0, 3500));
// update throttle cruise // update throttle cruise
// TO-DO: this may not be correct because g.rc_3.servo_out has not been updated for this iteration // TO-DO: this may not be correct because g.rc_3.servo_out has not been updated for this iteration
if( z_target_speed == 0 ) { if( z_target_speed == 0 ) {
......
ArduCopter Release Notes: ArduCopter Release Notes:
------------------------------------------------------------------ ------------------------------------------------------------------
ArduCopter 3.0.0 / 3.0.0-rc6 16-Jun-2013
Improvements over 3.0.0-rc5
1) bug fix to Circle mode's start position (was moving to last loiter target)
2) WP_ACCEL parameter added to allow user to adjust acceleration during missions
3) loiter acceleration set to half of LOIT_SPEED parameter value (was hard-coded)
4) reduce AltHold P to 1.0 (was 2.0)
------------------------------------------------------------------
ArduCopter 3.0.0-rc5 04-Jun-2013
Improvements over 3.0.0-rc4
1) bug fix to LAND flight mode in which it could try to fly to mission's next waypoint location
2) bug fix to Circle mode to allow counter-clockwise rotation
3) bug fix to heading change in Loiter, RTL, Missions when pilot's throttle is zero
4) bug fix for mission sticking at take-off command when pilot's throttle is zero
5) bug fix for parameters not saving when new value is same as default value
6) reduce pre-arm board min voltage check to 4.3V (was 4.5V)
7) remove throttle controller's ability to limit lean angle in loiter, rtl, auto
------------------------------------------------------------------
ArduCopter 3.0.0-rc4 02-Jun-2013 ArduCopter 3.0.0-rc4 02-Jun-2013
Improvements over 3.0.0-rc3 Improvements over 3.0.0-rc3
1) loiter improvements: 1) loiter improvements:
......
...@@ -323,9 +323,20 @@ static void do_land(const struct Location *cmd) ...@@ -323,9 +323,20 @@ static void do_land(const struct Location *cmd)
// set landing state // set landing state
land_state = LAND_STATE_DESCENDING; land_state = LAND_STATE_DESCENDING;
// switch to loiter which restores horizontal control to pilot // if we have gps lock, attempt to hold horizontal position
// To-Do: check that we are not in failsafe to ensure we don't process bad roll-pitch commands if( ap.home_is_set && g_gps->status() == GPS::GPS_OK_FIX_3D ) {
set_roll_pitch_mode(ROLL_PITCH_LOITER); // switch to loiter which restores horizontal control to pilot
// To-Do: check that we are not in failsafe to ensure we don't process bad roll-pitch commands
set_roll_pitch_mode(ROLL_PITCH_LOITER);
// switch into loiter nav mode
set_nav_mode(NAV_LOITER);
}else{
// no gps lock so give horizontal control to pilot
// To-Do: check that we are not in failsafe to ensure we don't process bad roll-pitch commands
set_roll_pitch_mode(ROLL_PITCH_STABLE);
// switch into loiter nav mode
set_nav_mode(NAV_NONE);
}
// hold yaw while landing // hold yaw while landing
set_yaw_mode(YAW_HOLD); set_yaw_mode(YAW_HOLD);
...@@ -333,8 +344,6 @@ static void do_land(const struct Location *cmd) ...@@ -333,8 +344,6 @@ static void do_land(const struct Location *cmd)
// set throttle mode to land // set throttle mode to land
set_throttle_mode(THROTTLE_LAND); set_throttle_mode(THROTTLE_LAND);
// switch into loiter nav mode
set_nav_mode(NAV_LOITER);
} }
} }
......
...@@ -918,7 +918,7 @@ ...@@ -918,7 +918,7 @@
#endif #endif
#ifndef ALT_HOLD_P #ifndef ALT_HOLD_P
# define ALT_HOLD_P 2.0f # define ALT_HOLD_P 1.0f
#endif #endif
#ifndef ALT_HOLD_I #ifndef ALT_HOLD_I
# define ALT_HOLD_I 0.0f # define ALT_HOLD_I 0.0f
......
...@@ -36,7 +36,7 @@ void fence_check() ...@@ -36,7 +36,7 @@ void fence_check()
init_disarm_motors(); init_disarm_motors();
}else{ }else{
// if we have a GPS // if we have a GPS
if( ap.home_is_set ) { if( ap.home_is_set && g_gps->status() == GPS::GPS_OK_FIX_3D ) {
// if we are within 100m of the fence, RTL // if we are within 100m of the fence, RTL
if( fence.get_breach_distance(new_breaches) <= AC_FENCE_GIVE_UP_DISTANCE) { if( fence.get_breach_distance(new_breaches) <= AC_FENCE_GIVE_UP_DISTANCE) {
if(control_mode != RTL) { if(control_mode != RTL) {
...@@ -44,7 +44,7 @@ void fence_check() ...@@ -44,7 +44,7 @@ void fence_check()
} }
}else{ }else{
// if more than 100m outside the fence just force a land // if more than 100m outside the fence just force a land
if(control_mode != RTL) { if(control_mode != LAND) {
set_mode(LAND); set_mode(LAND);
} }
} }
......
...@@ -68,7 +68,7 @@ static void calc_distance_and_bearing() ...@@ -68,7 +68,7 @@ static void calc_distance_and_bearing()
} }
// calculate home distance and bearing // calculate home distance and bearing
if( ap.home_is_set ) { if( ap.home_is_set && (g_gps->status() == GPS::GPS_OK_FIX_3D || g_gps->status() == GPS::GPS_OK_FIX_2D)) {
home_distance = pythagorous2(curr.x, curr.y); home_distance = pythagorous2(curr.x, curr.y);
home_bearing = pv_get_bearing_cd(curr,Vector3f(0,0,0)); home_bearing = pv_get_bearing_cd(curr,Vector3f(0,0,0));
...@@ -103,8 +103,8 @@ static void run_autopilot() ...@@ -103,8 +103,8 @@ static void run_autopilot()
// set_nav_mode - update nav mode and initialise any variables as required // set_nav_mode - update nav mode and initialise any variables as required
static bool set_nav_mode(uint8_t new_nav_mode) static bool set_nav_mode(uint8_t new_nav_mode)
{ {
// boolean to ensure proper initialisation of nav modes bool nav_initialised = false; // boolean to ensure proper initialisation of nav modes
bool nav_initialised = false; Vector3f stopping_point; // stopping point for circle mode
// return immediately if no change // return immediately if no change
if( new_nav_mode == nav_mode ) { if( new_nav_mode == nav_mode ) {
...@@ -119,13 +119,14 @@ static bool set_nav_mode(uint8_t new_nav_mode) ...@@ -119,13 +119,14 @@ static bool set_nav_mode(uint8_t new_nav_mode)
case NAV_CIRCLE: case NAV_CIRCLE:
// set center of circle to current position // set center of circle to current position
circle_set_center(inertial_nav.get_position(), ahrs.yaw); wp_nav.get_stopping_point(inertial_nav.get_position(),inertial_nav.get_velocity(),stopping_point);
circle_set_center(stopping_point,ahrs.yaw);
nav_initialised = true; nav_initialised = true;
break; break;
case NAV_LOITER: case NAV_LOITER:
// set target to current position // set target to current position
wp_nav.set_loiter_target(inertial_nav.get_position(), inertial_nav.get_velocity()); wp_nav.init_loiter_target(inertial_nav.get_position(), inertial_nav.get_velocity());
nav_initialised = true; nav_initialised = true;
break; break;
...@@ -217,13 +218,14 @@ static void ...@@ -217,13 +218,14 @@ static void
circle_set_center(const Vector3f current_position, float heading_in_radians) circle_set_center(const Vector3f current_position, float heading_in_radians)
{ {
float max_velocity; float max_velocity;
float cir_radius = g.circle_radius * 100;
// set circle center to circle_radius ahead of current position // set circle center to circle_radius ahead of current position
circle_center.x = current_position.x + (float)g.circle_radius * 100 * cos_yaw; circle_center.x = current_position.x + cir_radius * cos_yaw;
circle_center.y = current_position.y + (float)g.circle_radius * 100 * sin_yaw; circle_center.y = current_position.y + cir_radius * sin_yaw;
// if we are doing a panorama set the circle_angle to the current heading // if we are doing a panorama set the circle_angle to the current heading
if( g.circle_radius == 0 ) { if( g.circle_radius <= 0 ) {
circle_angle = heading_in_radians; circle_angle = heading_in_radians;
circle_angular_velocity_max = ToRad(g.circle_rate); circle_angular_velocity_max = ToRad(g.circle_rate);
circle_angular_acceleration = circle_angular_velocity_max; // reach maximum yaw velocity in 1 second circle_angular_acceleration = circle_angular_velocity_max; // reach maximum yaw velocity in 1 second
...@@ -235,13 +237,22 @@ circle_set_center(const Vector3f current_position, float heading_in_radians) ...@@ -235,13 +237,22 @@ circle_set_center(const Vector3f current_position, float heading_in_radians)
max_velocity = min(wp_nav.get_horizontal_velocity(), safe_sqrt(0.5f*WPNAV_ACCELERATION*g.circle_radius*100.0f)); max_velocity = min(wp_nav.get_horizontal_velocity(), safe_sqrt(0.5f*WPNAV_ACCELERATION*g.circle_radius*100.0f));
// angular_velocity in radians per second // angular_velocity in radians per second
circle_angular_velocity_max = min(ToRad(g.circle_rate), max_velocity/((float)g.circle_radius * 100.0f)); circle_angular_velocity_max = max_velocity/((float)g.circle_radius * 100.0f);
circle_angular_velocity_max = constrain_float(ToRad(g.circle_rate),-circle_angular_velocity_max,circle_angular_velocity_max);
// angular_velocity in radians per second
circle_angular_acceleration = WPNAV_ACCELERATION/((float)g.circle_radius * 100); circle_angular_acceleration = WPNAV_ACCELERATION/((float)g.circle_radius * 100);
if (g.circle_rate < 0.0f) {
circle_angular_acceleration = -circle_angular_acceleration;
}
} }
// initialise other variables // initialise other variables
circle_angle_total = 0; circle_angle_total = 0;
circle_angular_velocity = 0; circle_angular_velocity = 0;
// initialise loiter target. Note: feed forward velocity set to zero
wp_nav.init_loiter_target(current_position, Vector3f(0,0,0));
} }
// update_circle - circle position controller's main call which in turn calls loiter controller with updated target position // update_circle - circle position controller's main call which in turn calls loiter controller with updated target position
...@@ -252,9 +263,16 @@ update_circle(float dt) ...@@ -252,9 +263,16 @@ update_circle(float dt)
Vector3f circle_target; Vector3f circle_target;
// ramp up angular velocity to maximum // ramp up angular velocity to maximum
if(circle_angular_velocity < circle_angular_velocity_max){ if (g.circle_rate >= 0) {
circle_angular_velocity += circle_angular_acceleration * dt; if (circle_angular_velocity < circle_angular_velocity_max) {
circle_angular_velocity = constrain_float(circle_angular_velocity, 0, circle_angular_velocity_max); circle_angular_velocity += circle_angular_acceleration * dt;
circle_angular_velocity = constrain_float(circle_angular_velocity, 0, circle_angular_velocity_max);
}
}else{
if (circle_angular_velocity > circle_angular_velocity_max) {
circle_angular_velocity += circle_angular_acceleration * dt;
circle_angular_velocity = constrain_float(circle_angular_velocity, circle_angular_velocity_max, 0);
}
} }
// update the target angle // update the target angle
......
...@@ -434,7 +434,7 @@ static void set_mode(uint8_t mode) ...@@ -434,7 +434,7 @@ static void set_mode(uint8_t mode)
case LAND: case LAND:
// To-Do: it is messy to set manual_attitude here because the do_land function is reponsible for setting the roll_pitch_mode // To-Do: it is messy to set manual_attitude here because the do_land function is reponsible for setting the roll_pitch_mode
if( g_gps->status() == GPS::GPS_OK_FIX_3D ) { if( ap.home_is_set && g_gps->status() == GPS::GPS_OK_FIX_3D ) {
// switch to loiter if we have gps // switch to loiter if we have gps
ap.manual_attitude = false; ap.manual_attitude = false;
}else{ }else{
......
...@@ -10,7 +10,7 @@ const AP_Param::GroupInfo AC_WPNav::var_info[] PROGMEM = { ...@@ -10,7 +10,7 @@ const AP_Param::GroupInfo AC_WPNav::var_info[] PROGMEM = {
// @Param: SPEED // @Param: SPEED
// @DisplayName: Waypoint Horizontal Speed Target // @DisplayName: Waypoint Horizontal Speed Target
// @Description: Defines the speed in cm/s which the aircraft will attempt to maintain horizontally during a WP mission // @Description: Defines the speed in cm/s which the aircraft will attempt to maintain horizontally during a WP mission
// @Units: Centimeters/Second // @Units: cm/s
// @Range: 0 2000 // @Range: 0 2000
// @Increment: 50 // @Increment: 50
// @User: Standard // @User: Standard
...@@ -19,7 +19,7 @@ const AP_Param::GroupInfo AC_WPNav::var_info[] PROGMEM = { ...@@ -19,7 +19,7 @@ const AP_Param::GroupInfo AC_WPNav::var_info[] PROGMEM = {
// @Param: RADIUS // @Param: RADIUS
// @DisplayName: Waypoint Radius // @DisplayName: Waypoint Radius
// @Description: Defines the distance from a waypoint, that when crossed indicates the wp has been hit. // @Description: Defines the distance from a waypoint, that when crossed indicates the wp has been hit.
// @Units: Centimeters // @Units: cm
// @Range: 100 1000 // @Range: 100 1000
// @Increment: 1 // @Increment: 1
// @User: Standard // @User: Standard
...@@ -28,7 +28,7 @@ const AP_Param::GroupInfo AC_WPNav::var_info[] PROGMEM = { ...@@ -28,7 +28,7 @@ const AP_Param::GroupInfo AC_WPNav::var_info[] PROGMEM = {
// @Param: SPEED_UP // @Param: SPEED_UP
// @DisplayName: Waypoint Climb Speed Target // @DisplayName: Waypoint Climb Speed Target
// @Description: Defines the speed in cm/s which the aircraft will attempt to maintain while climbing during a WP mission // @Description: Defines the speed in cm/s which the aircraft will attempt to maintain while climbing during a WP mission
// @Units: Centimeters/Second // @Units: cm/s
// @Range: 0 1000 // @Range: 0 1000
// @Increment: 50 // @Increment: 50
// @User: Standard // @User: Standard
...@@ -37,7 +37,7 @@ const AP_Param::GroupInfo AC_WPNav::var_info[] PROGMEM = { ...@@ -37,7 +37,7 @@ const AP_Param::GroupInfo AC_WPNav::var_info[] PROGMEM = {
// @Param: SPEED_DN // @Param: SPEED_DN
// @DisplayName: Waypoint Descent Speed Target // @DisplayName: Waypoint Descent Speed Target
// @Description: Defines the speed in cm/s which the aircraft will attempt to maintain while descending during a WP mission // @Description: Defines the speed in cm/s which the aircraft will attempt to maintain while descending during a WP mission
// @Units: Centimeters/Second // @Units: cm/s
// @Range: 0 1000 // @Range: 0 1000
// @Increment: 50 // @Increment: 50
// @User: Standard // @User: Standard
...@@ -46,12 +46,21 @@ const AP_Param::GroupInfo AC_WPNav::var_info[] PROGMEM = { ...@@ -46,12 +46,21 @@ const AP_Param::GroupInfo AC_WPNav::var_info[] PROGMEM = {
// @Param: LOIT_SPEED // @Param: LOIT_SPEED
// @DisplayName: Loiter Horizontal Maximum Speed // @DisplayName: Loiter Horizontal Maximum Speed
// @Description: Defines the maximum speed in cm/s which the aircraft will travel horizontally while in loiter mode // @Description: Defines the maximum speed in cm/s which the aircraft will travel horizontally while in loiter mode
// @Units: Centimeters/Second // @Units: cm/s
// @Range: 0 2000 // @Range: 0 2000
// @Increment: 50 // @Increment: 50
// @User: Standard // @User: Standard
AP_GROUPINFO("LOIT_SPEED", 4, AC_WPNav, _loiter_speed_cms, WPNAV_LOITER_SPEED), AP_GROUPINFO("LOIT_SPEED", 4, AC_WPNav, _loiter_speed_cms, WPNAV_LOITER_SPEED),
// @Param: ACCEL
// @DisplayName: Waypoint Acceleration
// @Description: Defines the horizontal acceleration in cm/s/s used during missions
// @Units: cm/s/s
// @Range: 0 980
// @Increment: 10
// @User: Standard
AP_GROUPINFO("ACCEL", 5, AC_WPNav, _wp_accel_cms, WPNAV_ACCELERATION),
AP_GROUPEND AP_GROUPEND
}; };
...@@ -81,6 +90,7 @@ AC_WPNav::AC_WPNav(AP_InertialNav* inav, AP_AHRS* ahrs, APM_PI* pid_pos_lat, APM ...@@ -81,6 +90,7 @@ AC_WPNav::AC_WPNav(AP_InertialNav* inav, AP_AHRS* ahrs, APM_PI* pid_pos_lat, APM
_vel_last(0,0,0), _vel_last(0,0,0),
_lean_angle_max(MAX_LEAN_ANGLE), _lean_angle_max(MAX_LEAN_ANGLE),
_loiter_leash(WPNAV_MIN_LEASH_LENGTH), _loiter_leash(WPNAV_MIN_LEASH_LENGTH),
_loiter_accel_cms(WPNAV_LOITER_ACCEL_MAX),
_wp_leash_xy(WPNAV_MIN_LEASH_LENGTH), _wp_leash_xy(WPNAV_MIN_LEASH_LENGTH),
_wp_leash_z(WPNAV_MIN_LEASH_LENGTH), _wp_leash_z(WPNAV_MIN_LEASH_LENGTH),
_track_accel(0), _track_accel(0),
...@@ -112,23 +122,23 @@ void AC_WPNav::get_stopping_point(const Vector3f& position, const Vector3f& velo ...@@ -112,23 +122,23 @@ void AC_WPNav::get_stopping_point(const Vector3f& position, const Vector3f& velo
// calculate current velocity // calculate current velocity
vel_total = safe_sqrt(velocity.x*velocity.x + velocity.y*velocity.y); vel_total = safe_sqrt(velocity.x*velocity.x + velocity.y*velocity.y);
// avoid divide by zero by using current position if the velocity is below 10cm/s or kP is very low // avoid divide by zero by using current position if the velocity is below 10cm/s, kP is very low or acceleration is zero
if (vel_total < 10.0f || kP <= 0.0f) { if (vel_total < 10.0f || kP <= 0.0f || _wp_accel_cms <= 0.0f) {
target = position; target = position;
return; return;
} }
// calculate point at which velocity switches from linear to sqrt // calculate point at which velocity switches from linear to sqrt
linear_velocity = WPNAV_ACCELERATION/kP; linear_velocity = _wp_accel_cms/kP;
// calculate distance within which we can stop // calculate distance within which we can stop
if (vel_total < linear_velocity) { if (vel_total < linear_velocity) {
target_dist = vel_total/kP; target_dist = vel_total/kP;
} else { } else {
linear_distance = WPNAV_ACCELERATION/(2*kP*kP); linear_distance = _wp_accel_cms/(2.0f*kP*kP);
target_dist = linear_distance + (vel_total*vel_total)/(2*WPNAV_ACCELERATION); target_dist = linear_distance + (vel_total*vel_total)/(2.0f*_wp_accel_cms);
} }
target_dist = constrain_float(target_dist, 0, _loiter_leash*2.0); target_dist = constrain_float(target_dist, 0, _loiter_leash*2.0f);
target.x = position.x + (target_dist * velocity.x / vel_total); target.x = position.x + (target_dist * velocity.x / vel_total);
target.y = position.y + (target_dist * velocity.y / vel_total); target.y = position.y + (target_dist * velocity.y / vel_total);
...@@ -143,8 +153,8 @@ void AC_WPNav::set_loiter_target(const Vector3f& position) ...@@ -143,8 +153,8 @@ void AC_WPNav::set_loiter_target(const Vector3f& position)
_target_vel.y = 0; _target_vel.y = 0;
} }
/// set_loiter_target - set initial loiter target based on current position and velocity /// init_loiter_target - set initial loiter target based on current position and velocity
void AC_WPNav::set_loiter_target(const Vector3f& position, const Vector3f& velocity) void AC_WPNav::init_loiter_target(const Vector3f& position, const Vector3f& velocity)
{ {
// set target position and velocity based on current pos and velocity // set target position and velocity based on current pos and velocity
_target.x = position.x; _target.x = position.x;
...@@ -155,6 +165,14 @@ void AC_WPNav::set_loiter_target(const Vector3f& position, const Vector3f& veloc ...@@ -155,6 +165,14 @@ void AC_WPNav::set_loiter_target(const Vector3f& position, const Vector3f& veloc
// initialise desired roll and pitch to current roll and pitch. This avoids a random twitch between now and when the loiter controller is first run // initialise desired roll and pitch to current roll and pitch. This avoids a random twitch between now and when the loiter controller is first run
_desired_roll = constrain_int32(_ahrs->roll_sensor,-MAX_LEAN_ANGLE,MAX_LEAN_ANGLE); _desired_roll = constrain_int32(_ahrs->roll_sensor,-MAX_LEAN_ANGLE,MAX_LEAN_ANGLE);
_desired_pitch = constrain_int32(_ahrs->pitch_sensor,-MAX_LEAN_ANGLE,MAX_LEAN_ANGLE); _desired_pitch = constrain_int32(_ahrs->pitch_sensor,-MAX_LEAN_ANGLE,MAX_LEAN_ANGLE);
// initialise pilot input
_pilot_vel_forward_cms = 0;
_pilot_vel_right_cms = 0;
// set last velocity to current velocity
// To-Do: remove the line below by instead forcing reset_I to be called on the first loiter_update call
_vel_last = _inav->get_velocity();
} }
/// move_loiter_target - move loiter target by velocity provided in front/right directions in cm/s /// move_loiter_target - move loiter target by velocity provided in front/right directions in cm/s
...@@ -263,24 +281,28 @@ void AC_WPNav::calculate_loiter_leash_length() ...@@ -263,24 +281,28 @@ void AC_WPNav::calculate_loiter_leash_length()
float kP = _pid_pos_lat->kP(); float kP = _pid_pos_lat->kP();
// avoid divide by zero // avoid divide by zero
if (kP <= 0.0f) { if (kP <= 0.0f || _wp_accel_cms <= 0.0f) {
_loiter_leash = WPNAV_MIN_LEASH_LENGTH; _loiter_leash = WPNAV_MIN_LEASH_LENGTH;
_loiter_accel_cms = _loiter_leash / 2.0f; // set loiter acceleration to 1/2 loiter speed
return; return;
} }
// calculate horiztonal leash length // calculate horiztonal leash length
if(_loiter_speed_cms <= WPNAV_ACCELERATION / kP) { if(_loiter_speed_cms <= _wp_accel_cms / kP) {
// linear leash length based on speed close in // linear leash length based on speed close in
_loiter_leash = _loiter_speed_cms / kP; _loiter_leash = _loiter_speed_cms / kP;
}else{ }else{
// leash length grows at sqrt of speed further out // leash length grows at sqrt of speed further out
_loiter_leash = (WPNAV_ACCELERATION / (2.0*kP*kP)) + (_loiter_speed_cms*_loiter_speed_cms / (2*WPNAV_ACCELERATION)); _loiter_leash = (_wp_accel_cms / (2.0f*kP*kP)) + (_loiter_speed_cms*_loiter_speed_cms / (2.0f*_wp_accel_cms));
} }
// ensure leash is at least 1m long // ensure leash is at least 1m long
if( _loiter_leash < WPNAV_MIN_LEASH_LENGTH ) { if( _loiter_leash < WPNAV_MIN_LEASH_LENGTH ) {
_loiter_leash = WPNAV_MIN_LEASH_LENGTH; _loiter_leash = WPNAV_MIN_LEASH_LENGTH;
} }
// set loiter acceleration to 1/2 loiter speed
_loiter_accel_cms = _loiter_leash / 2.0f;
} }
/// ///
...@@ -504,12 +526,12 @@ void AC_WPNav::get_loiter_position_to_velocity(float dt, float max_speed_cms) ...@@ -504,12 +526,12 @@ void AC_WPNav::get_loiter_position_to_velocity(float dt, float max_speed_cms)
dist_error.x = _target.x - curr.x; dist_error.x = _target.x - curr.x;
dist_error.y = _target.y - curr.y; dist_error.y = _target.y - curr.y;
linear_distance = WPNAV_ACCELERATION/(2*kP*kP); linear_distance = _wp_accel_cms/(2.0f*kP*kP);
_distance_to_target = linear_distance; // for reporting purposes _distance_to_target = linear_distance; // for reporting purposes
dist_error_total = safe_sqrt(dist_error.x*dist_error.x + dist_error.y*dist_error.y); dist_error_total = safe_sqrt(dist_error.x*dist_error.x + dist_error.y*dist_error.y);
if( dist_error_total > 2*linear_distance ) { if( dist_error_total > 2.0f*linear_distance ) {
vel_sqrt = safe_sqrt(2*WPNAV_ACCELERATION*(dist_error_total-linear_distance)); vel_sqrt = safe_sqrt(2.0f*_wp_accel_cms*(dist_error_total-linear_distance));
desired_vel.x = vel_sqrt * dist_error.x/dist_error_total; desired_vel.x = vel_sqrt * dist_error.x/dist_error_total;
desired_vel.y = vel_sqrt * dist_error.y/dist_error_total; desired_vel.y = vel_sqrt * dist_error.y/dist_error_total;
}else{ }else{
...@@ -623,18 +645,23 @@ void AC_WPNav::calculate_wp_leash_length(bool climb) ...@@ -623,18 +645,23 @@ void AC_WPNav::calculate_wp_leash_length(bool climb)
// get loiter position P // get loiter position P
float kP = _pid_pos_lat->kP(); float kP = _pid_pos_lat->kP();
// sanity check acceleration and avoid divide by zero
if (_wp_accel_cms <= 0.0f) {
_wp_accel_cms = WPNAV_ACCELERATION_MIN;
}
// avoid divide by zero // avoid divide by zero
if (kP <= 0.0f) { if (kP <= 0.0f) {
_wp_leash_xy = WPNAV_MIN_LEASH_LENGTH; _wp_leash_xy = WPNAV_MIN_LEASH_LENGTH;
return; return;
} }
// calculate horiztonal leash length // calculate horiztonal leash length
if(_wp_speed_cms <= WPNAV_ACCELERATION / kP) { if(_wp_speed_cms <= _wp_accel_cms / kP) {
// linear leash length based on speed close in // linear leash length based on speed close in
_wp_leash_xy = _wp_speed_cms / kP; _wp_leash_xy = _wp_speed_cms / kP;
}else{ }else{
// leash length grows at sqrt of speed further out // leash length grows at sqrt of speed further out
_wp_leash_xy = (WPNAV_ACCELERATION / (2.0*kP*kP)) + (_wp_speed_cms*_wp_speed_cms / (2*WPNAV_ACCELERATION)); _wp_leash_xy = (_wp_accel_cms / (2.0f*kP*kP)) + (_wp_speed_cms*_wp_speed_cms / (2.0f*_wp_accel_cms));
} }
// ensure leash is at least 1m long // ensure leash is at least 1m long
...@@ -672,7 +699,7 @@ void AC_WPNav::calculate_wp_leash_length(bool climb) ...@@ -672,7 +699,7 @@ void AC_WPNav::calculate_wp_leash_length(bool climb)
_track_speed = 0; _track_speed = 0;
_track_leash_length = WPNAV_MIN_LEASH_LENGTH; _track_leash_length = WPNAV_MIN_LEASH_LENGTH;
}else if(_pos_delta_unit.z == 0){ }else if(_pos_delta_unit.z == 0){
_track_accel = WPNAV_ACCELERATION/pos_delta_unit_xy; _track_accel = _wp_accel_cms/pos_delta_unit_xy;
_track_speed = _wp_speed_cms/pos_delta_unit_xy; _track_speed = _wp_speed_cms/pos_delta_unit_xy;
_track_leash_length = _wp_leash_xy/pos_delta_unit_xy; _track_leash_length = _wp_leash_xy/pos_delta_unit_xy;
}else if(pos_delta_unit_xy == 0){ }else if(pos_delta_unit_xy == 0){
...@@ -680,7 +707,7 @@ void AC_WPNav::calculate_wp_leash_length(bool climb) ...@@ -680,7 +707,7 @@ void AC_WPNav::calculate_wp_leash_length(bool climb)
_track_speed = speed_vert/pos_delta_unit_z; _track_speed = speed_vert/pos_delta_unit_z;
_track_leash_length = _wp_leash_z/pos_delta_unit_z; _track_leash_length = _wp_leash_z/pos_delta_unit_z;
}else{ }else{
_track_accel = min(WPNAV_ALT_HOLD_ACCEL_MAX/pos_delta_unit_z, WPNAV_ACCELERATION/pos_delta_unit_xy); _track_accel = min(WPNAV_ALT_HOLD_ACCEL_MAX/pos_delta_unit_z, _wp_accel_cms/pos_delta_unit_xy);
_track_speed = min(speed_vert/pos_delta_unit_z, _wp_speed_cms/pos_delta_unit_xy); _track_speed = min(speed_vert/pos_delta_unit_z, _wp_speed_cms/pos_delta_unit_xy);
_track_leash_length = min(_wp_leash_z/pos_delta_unit_z, _wp_leash_xy/pos_delta_unit_xy); _track_leash_length = min(_wp_leash_z/pos_delta_unit_z, _wp_leash_xy/pos_delta_unit_xy);
} }
......
...@@ -11,7 +11,8 @@ ...@@ -11,7 +11,8 @@
#include <AP_InertialNav.h> // Inertial Navigation library #include <AP_InertialNav.h> // Inertial Navigation library
// loiter maximum velocities and accelerations // loiter maximum velocities and accelerations
#define WPNAV_ACCELERATION 250.0f // defines the velocity vs distant curve. maximum acceleration in cm/s/s that position controller asks for from acceleration controller #define WPNAV_ACCELERATION 250.0f // defines the default velocity vs distant curve. maximum acceleration in cm/s/s that position controller asks for from acceleration controller
#define WPNAV_ACCELERATION_MIN 50.0f // minimum acceleration in cm/s/s - used for sanity checking _wp_accel parameter
#define WPNAV_ACCEL_MAX 980.0f // max acceleration in cm/s/s that the loiter velocity controller will ask from the lower accel controller. #define WPNAV_ACCEL_MAX 980.0f // max acceleration in cm/s/s that the loiter velocity controller will ask from the lower accel controller.
// should be 1.5 times larger than WPNAV_ACCELERATION. // should be 1.5 times larger than WPNAV_ACCELERATION.
// max acceleration = max lean angle * 980 * pi / 180. i.e. 23deg * 980 * 3.141 / 180 = 393 cm/s/s // max acceleration = max lean angle * 980 * pi / 180. i.e. 23deg * 980 * 3.141 / 180 = 393 cm/s/s
...@@ -50,8 +51,8 @@ public: ...@@ -50,8 +51,8 @@ public:
/// set_loiter_target in cm from home /// set_loiter_target in cm from home
void set_loiter_target(const Vector3f& position); void set_loiter_target(const Vector3f& position);
/// set_loiter_target - set initial loiter target based on current position and velocity /// init_loiter_target - set initial loiter target based on current position and velocity
void set_loiter_target(const Vector3f& position, const Vector3f& velocity); void init_loiter_target(const Vector3f& position, const Vector3f& velocity);
/// move_loiter_target - move destination using pilot input /// move_loiter_target - move destination using pilot input
void move_loiter_target(float control_roll, float control_pitch, float dt); void move_loiter_target(float control_roll, float control_pitch, float dt);
...@@ -200,6 +201,7 @@ protected: ...@@ -200,6 +201,7 @@ protected:
AP_Float _wp_speed_up_cms; // climb speed target in cm/s AP_Float _wp_speed_up_cms; // climb speed target in cm/s
AP_Float _wp_speed_down_cms; // descent speed target in cm/s AP_Float _wp_speed_down_cms; // descent speed target in cm/s
AP_Float _wp_radius_cm; // distance from a waypoint in cm that, when crossed, indicates the wp has been reached AP_Float _wp_radius_cm; // distance from a waypoint in cm that, when crossed, indicates the wp has been reached
AP_Float _wp_accel_cms; // acceleration in cm/s/s during missions
uint32_t _loiter_last_update; // time of last update_loiter call uint32_t _loiter_last_update; // time of last update_loiter call
uint32_t _wpnav_last_update; // time of last update_wpnav call uint32_t _wpnav_last_update; // time of last update_wpnav call
float _cos_yaw; // short-cut to save on calcs required to convert roll-pitch frame to lat-lon frame float _cos_yaw; // short-cut to save on calcs required to convert roll-pitch frame to lat-lon frame
...@@ -219,6 +221,7 @@ protected: ...@@ -219,6 +221,7 @@ protected:
Vector3f _vel_last; // previous iterations velocity in cm/s Vector3f _vel_last; // previous iterations velocity in cm/s
int32_t _lean_angle_max; // maximum lean angle. can be set from main code so that throttle controller can stop leans that cause copter to lose altitude int32_t _lean_angle_max; // maximum lean angle. can be set from main code so that throttle controller can stop leans that cause copter to lose altitude
float _loiter_leash; // loiter's horizontal leash length in cm. used to stop the pilot from pushing the target location too far from the current location float _loiter_leash; // loiter's horizontal leash length in cm. used to stop the pilot from pushing the target location too far from the current location
float _loiter_accel_cms; // loiter's acceleration in cm/s/s
// waypoint controller internal variables // waypoint controller internal variables
Vector3f _origin; // starting point of trip to next waypoint in cm from home (equivalent to next_WP) Vector3f _origin; // starting point of trip to next waypoint in cm from home (equivalent to next_WP)
......
...@@ -477,7 +477,7 @@ bool AP_InertialSensor::_calibrate_accel( Vector3f accel_sample[6], ...@@ -477,7 +477,7 @@ bool AP_InertialSensor::_calibrate_accel( Vector3f accel_sample[6],
success = false; success = false;
} }
// sanity check offsets (2.0 is roughly 2/10th of a G, 5.0 is roughly half a G) // sanity check offsets (2.0 is roughly 2/10th of a G, 5.0 is roughly half a G)
if( accel_offsets.is_nan() || fabsf(accel_offsets.x) > 2.0f || fabsf(accel_offsets.y) > 2.0f || fabsf(accel_offsets.z) > 3.0f ) { if( accel_offsets.is_nan() || fabsf(accel_offsets.x) > 3.0f || fabsf(accel_offsets.y) > 3.0f || fabsf(accel_offsets.z) > 3.0f ) {
success = false; success = false;
} }
......