Copter: remove non-inav loiter and wp controllers
lon_speed, lat_speed changed to float do_takeoff, do_land now set roll-pitch, yaw and nav modes specifically removed fast_corners functionality (may need to be reimplemented with new inertial nav controllers)
This commit is contained in:
parent
609676e26c
commit
cbde042ec5
@ -356,17 +356,15 @@ static union {
|
||||
uint8_t manual_throttle : 1; // 4
|
||||
|
||||
uint8_t low_battery : 1; // 5 // Used to track if the battery is low - LED output flashes when the batt is low
|
||||
uint8_t loiter_override : 1; // 6 // Are we navigating while holding a positon? This is set to false once the speed drops below 1m/s
|
||||
uint8_t armed : 1; // 7
|
||||
uint8_t auto_armed : 1; // 8
|
||||
uint8_t armed : 1; // 6
|
||||
uint8_t auto_armed : 1; // 7
|
||||
|
||||
uint8_t failsafe : 1; // 9 // A status flag for the failsafe state
|
||||
uint8_t do_flip : 1; // 10 // Used to enable flip code
|
||||
uint8_t takeoff_complete : 1; // 11
|
||||
uint8_t land_complete : 1; // 12
|
||||
uint8_t compass_status : 1; // 13
|
||||
uint8_t gps_status : 1; // 14
|
||||
uint8_t fast_corner : 1; // 15 // should we take the waypoint quickly or slow down?
|
||||
uint8_t failsafe : 1; // 8 // A status flag for the failsafe state
|
||||
uint8_t do_flip : 1; // 9 // Used to enable flip code
|
||||
uint8_t takeoff_complete : 1; // 10
|
||||
uint8_t land_complete : 1; // 11
|
||||
uint8_t compass_status : 1; // 12
|
||||
uint8_t gps_status : 1; // 13
|
||||
};
|
||||
uint16_t value;
|
||||
} ap;
|
||||
@ -384,28 +382,6 @@ static struct AP_System{
|
||||
|
||||
} ap_system;
|
||||
|
||||
/*
|
||||
what navigation updated are needed
|
||||
*/
|
||||
static struct nav_updates {
|
||||
uint8_t need_velpos : 1;
|
||||
uint8_t need_dist_bearing : 1;
|
||||
uint8_t need_nav_controllers : 1;
|
||||
uint8_t need_nav_pitch_roll : 1;
|
||||
} nav_updates;
|
||||
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// velocity in lon and lat directions calculated from GPS position and accelerometer data
|
||||
// updated after GPS read - 5-10hz
|
||||
static int16_t lon_speed; // expressed in cm/s. positive numbers mean moving east
|
||||
static int16_t lat_speed; // expressed in cm/s. positive numbers when moving north
|
||||
|
||||
// The difference between the desired rate of travel and the actual rate of travel
|
||||
// updated after GPS read - 5-10hz
|
||||
static int16_t x_rate_error;
|
||||
static int16_t y_rate_error;
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Radio
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
@ -525,11 +501,7 @@ static uint8_t command_cond_index;
|
||||
// NAV_LOCATION - have we reached the desired location?
|
||||
// NAV_DELAY - have we waited at the waypoint the desired time?
|
||||
static uint8_t wp_verify_byte; // used for tracking state of navigating waypoints
|
||||
// used to limit the speed ramp up of WP navigation
|
||||
// Acceleration is limited to 1m/s/s
|
||||
static int16_t max_speed_old;
|
||||
// Used to track how many cm we are from the "next_WP" location
|
||||
static int32_t long_error, lat_error;
|
||||
static float lon_error, lat_error; // Used to report how many cm we are from the next waypoint or loiter target position
|
||||
static int16_t control_roll;
|
||||
static int16_t control_pitch;
|
||||
static uint8_t rtl_state;
|
||||
@ -618,8 +590,8 @@ static uint32_t loiter_time;
|
||||
// The synthetic location created to make the copter do circles around a WP
|
||||
static struct Location circle_WP;
|
||||
// inertial nav loiter variables
|
||||
static float loiter_lat_from_home_cm;
|
||||
static float loiter_lon_from_home_cm;
|
||||
static float loiter_lat_from_home_cm; // loiter's target latitude in cm from home
|
||||
static float loiter_lon_from_home_cm; // loiter's target longitude in cm from home
|
||||
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
@ -919,11 +891,11 @@ AP_Param param_loader(var_info, WP_START_BYTE);
|
||||
*/
|
||||
static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = {
|
||||
{ update_GPS, 2, 900 },
|
||||
{ update_navigation, 2, 500 },
|
||||
{ update_navigation, 10, 500 },
|
||||
{ medium_loop, 2, 700 },
|
||||
{ update_altitude, 5, 1000 },
|
||||
{ fifty_hz_loop, 2, 950 },
|
||||
{ run_nav_updates, 2, 500 },
|
||||
{ run_nav_updates, 10, 800 },
|
||||
{ slow_loop, 10, 500 },
|
||||
{ gcs_check_input, 2, 700 },
|
||||
{ gcs_send_heartbeat, 100, 700 },
|
||||
@ -1614,8 +1586,7 @@ bool set_roll_pitch_mode(uint8_t new_roll_pitch_mode)
|
||||
roll_pitch_initialised = true;
|
||||
break;
|
||||
|
||||
case ROLL_PITCH_LOITER_INAV:
|
||||
case ROLL_PITCH_WP_INAV:
|
||||
case ROLL_PITCH_LOITER:
|
||||
// require gps lock
|
||||
if( ap.home_is_set ) {
|
||||
roll_pitch_initialised = true;
|
||||
@ -1680,19 +1651,15 @@ void update_roll_pitch_mode(void)
|
||||
break;
|
||||
|
||||
case ROLL_PITCH_AUTO:
|
||||
// apply SIMPLE mode transform
|
||||
if(ap.simple_mode && ap_system.new_radio_frame) {
|
||||
update_simple_mode();
|
||||
}
|
||||
// mix in user control with Nav control
|
||||
nav_roll += constrain_int32(wrap_180(auto_roll - nav_roll), -g.auto_slew_rate.get(), g.auto_slew_rate.get()); // 40 deg a second
|
||||
nav_pitch += constrain_int32(wrap_180(auto_pitch - nav_pitch), -g.auto_slew_rate.get(), g.auto_slew_rate.get()); // 40 deg a second
|
||||
// copy latest output from nav controller to stabilize controller
|
||||
nav_roll = auto_roll;
|
||||
nav_pitch = auto_pitch;
|
||||
get_stabilize_roll(nav_roll);
|
||||
get_stabilize_pitch(nav_pitch);
|
||||
|
||||
control_roll = g.rc_1.control_mix(nav_roll);
|
||||
control_pitch = g.rc_2.control_mix(nav_pitch);
|
||||
|
||||
get_stabilize_roll(control_roll);
|
||||
get_stabilize_pitch(control_pitch);
|
||||
// copy control_roll and pitch for reporting purposes
|
||||
control_roll = nav_roll;
|
||||
control_pitch = nav_pitch;
|
||||
break;
|
||||
|
||||
case ROLL_PITCH_STABLE_OF:
|
||||
@ -1715,7 +1682,7 @@ void update_roll_pitch_mode(void)
|
||||
roll_pitch_toy();
|
||||
break;
|
||||
|
||||
case ROLL_PITCH_LOITER_INAV:
|
||||
case ROLL_PITCH_LOITER:
|
||||
// apply SIMPLE mode transform
|
||||
if(ap.simple_mode && ap_system.new_radio_frame) {
|
||||
update_simple_mode();
|
||||
@ -1735,15 +1702,6 @@ void update_roll_pitch_mode(void)
|
||||
get_stabilize_roll(nav_roll);
|
||||
get_stabilize_pitch(nav_pitch);
|
||||
break;
|
||||
|
||||
case ROLL_PITCH_WP_INAV:
|
||||
// To-Do: allow pilot to take control of target location
|
||||
// copy latest output from nav controller to stabilize controller
|
||||
nav_roll = auto_roll;
|
||||
nav_pitch = auto_pitch;
|
||||
get_stabilize_roll(nav_roll);
|
||||
get_stabilize_pitch(nav_pitch);
|
||||
break;
|
||||
}
|
||||
|
||||
#if FRAME_CONFIG != HELI_FRAME
|
||||
@ -2253,9 +2211,8 @@ static void tuning(){
|
||||
#endif
|
||||
|
||||
case CH6_INAV_TC:
|
||||
#if INERTIAL_NAV_XY == ENABLED
|
||||
// To-Do: allowing tuning TC for xy and z separately
|
||||
inertial_nav.set_time_constant_xy(tuning_value);
|
||||
#endif
|
||||
inertial_nav.set_time_constant_z(tuning_value);
|
||||
break;
|
||||
|
||||
|
@ -489,13 +489,13 @@ static void Log_Read_Optflow()
|
||||
struct log_Nav_Tuning {
|
||||
LOG_PACKET_HEADER;
|
||||
uint32_t wp_distance;
|
||||
int16_t wp_bearing;
|
||||
int16_t lat_error;
|
||||
int16_t lon_error;
|
||||
int16_t nav_pitch;
|
||||
int16_t nav_roll;
|
||||
int16_t lat_speed;
|
||||
int16_t lon_speed;
|
||||
int16_t wp_bearing;
|
||||
float lat_error;
|
||||
float lon_error;
|
||||
int16_t nav_pitch;
|
||||
int16_t nav_roll;
|
||||
int16_t lat_speed;
|
||||
int16_t lon_speed;
|
||||
};
|
||||
|
||||
// Write an Nav Tuning packet. Total length : 24 bytes
|
||||
@ -505,12 +505,12 @@ static void Log_Write_Nav_Tuning()
|
||||
LOG_PACKET_HEADER_INIT(LOG_NAV_TUNING_MSG),
|
||||
wp_distance : wp_distance,
|
||||
wp_bearing : (int16_t) (wp_bearing/100),
|
||||
lat_error : (int16_t) lat_error,
|
||||
lon_error : (int16_t) long_error,
|
||||
lat_error : lat_error,
|
||||
lon_error : lon_error,
|
||||
nav_pitch : (int16_t) nav_pitch,
|
||||
nav_roll : (int16_t) nav_roll,
|
||||
lat_speed : lat_speed,
|
||||
lon_speed : lon_speed
|
||||
lat_speed : (int16_t) inertial_nav.get_latitude_velocity(),
|
||||
lon_speed : (int16_t) inertial_nav.get_longitude_velocity()
|
||||
};
|
||||
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
@ -521,12 +521,12 @@ static void Log_Read_Nav_Tuning()
|
||||
struct log_Nav_Tuning pkt;
|
||||
DataFlash.ReadPacket(&pkt, sizeof(pkt));
|
||||
|
||||
// 1 2 3 4 5 6 7 8
|
||||
cliSerial->printf_P(PSTR("NTUN, %lu, %d, %d, %d, %d, %d, %d, %d\n"),
|
||||
// 1 2 3 4 5 6 7 8
|
||||
cliSerial->printf_P(PSTR("NTUN, %lu, %d, %.0f, %.0f, %d, %d, %d, %d\n"),
|
||||
(unsigned long)pkt.wp_distance,
|
||||
(int)pkt.wp_bearing,
|
||||
(int)pkt.lat_error,
|
||||
(int)pkt.lon_error,
|
||||
(float)pkt.lat_error,
|
||||
(float)pkt.lon_error,
|
||||
(int)pkt.nav_pitch,
|
||||
(int)pkt.nav_roll,
|
||||
(int)pkt.lat_speed,
|
||||
|
@ -8,9 +8,6 @@ static void init_commands()
|
||||
prev_nav_index = NO_COMMAND;
|
||||
command_cond_queue.id = NO_COMMAND;
|
||||
command_nav_queue.id = NO_COMMAND;
|
||||
|
||||
ap.fast_corner = false;
|
||||
reset_desired_speed();
|
||||
}
|
||||
|
||||
// Getters
|
||||
@ -154,9 +151,6 @@ static void set_next_WP(struct Location *wp)
|
||||
wp_distance = get_distance_cm(¤t_loc, &next_WP);
|
||||
wp_bearing = get_bearing_cd(&prev_WP, &next_WP);
|
||||
original_wp_bearing = wp_bearing; // to check if we have missed the WP
|
||||
|
||||
// calc the location error:
|
||||
calc_location_error(&next_WP);
|
||||
}
|
||||
|
||||
// set_next_WP_latlon - update just lat and lon targets for nav controllers
|
||||
@ -191,10 +185,8 @@ static void init_home()
|
||||
// no need to save this to EPROM
|
||||
set_cmd_with_index(home, 0);
|
||||
|
||||
#if INERTIAL_NAV_XY == ENABLED
|
||||
// set inertial nav's home position
|
||||
inertial_nav.set_current_position(g_gps->longitude, g_gps->latitude);
|
||||
#endif
|
||||
|
||||
if (g.log_bitmask & MASK_LOG_CMD)
|
||||
Log_Write_Cmd(0, &home);
|
||||
|
@ -226,7 +226,7 @@ static void do_RTL(void)
|
||||
set_throttle_mode(RTL_THR);
|
||||
|
||||
// set navigation mode
|
||||
set_nav_mode(NAV_LOITER_ACTIVE);
|
||||
set_nav_mode(NAV_LOITER);
|
||||
|
||||
// override altitude to RTL altitude
|
||||
set_new_altitude(get_RTL_alt());
|
||||
@ -239,11 +239,11 @@ static void do_RTL(void)
|
||||
// do_takeoff - initiate takeoff navigation command
|
||||
static void do_takeoff()
|
||||
{
|
||||
// set our yaw mode
|
||||
set_yaw_mode(YAW_HOLD);
|
||||
// set roll-pitch mode
|
||||
set_roll_pitch_mode(AUTO_RP);
|
||||
|
||||
// set our nav mode to loiter
|
||||
set_nav_mode(NAV_LOITER_ACTIVE);
|
||||
// set yaw mode
|
||||
set_yaw_mode(YAW_HOLD);
|
||||
|
||||
// set throttle mode to AUTO although we should already be in this mode
|
||||
set_throttle_mode(THROTTLE_AUTO);
|
||||
@ -251,30 +251,31 @@ static void do_takeoff()
|
||||
// set target altitude
|
||||
set_new_altitude(command_nav_queue.alt);
|
||||
|
||||
// set our nav mode to loiter
|
||||
set_nav_mode(NAV_LOITER);
|
||||
|
||||
// prevent flips
|
||||
// To-Do: check if this is still necessary
|
||||
reset_I_all();
|
||||
}
|
||||
|
||||
// do_nav_wp - initiate move to next waypoint
|
||||
// note: caller should set yaw mode
|
||||
static void do_nav_wp()
|
||||
{
|
||||
// set nav mode
|
||||
set_nav_mode(NAV_WP_ACTIVE);
|
||||
// set roll-pitch mode
|
||||
set_roll_pitch_mode(AUTO_RP);
|
||||
|
||||
// set target location
|
||||
#if NAV_WP_ACTIVE == NAV_WP
|
||||
// Set navigation target
|
||||
set_next_WP(&command_nav_queue);
|
||||
#else
|
||||
// Set inav navigation target
|
||||
wpinav_set_destination(command_nav_queue);
|
||||
#endif
|
||||
|
||||
// set throttle mode to AUTO although we are likely already in this mode
|
||||
// set throttle mode
|
||||
set_throttle_mode(THROTTLE_AUTO);
|
||||
set_new_altitude(command_nav_queue.alt);
|
||||
|
||||
// set nav mode
|
||||
set_nav_mode(NAV_WP);
|
||||
|
||||
// Set inav navigation target
|
||||
wpinav_set_destination(command_nav_queue);
|
||||
|
||||
// this is our bitmask to verify we have met all conditions to move on
|
||||
wp_verify_byte = 0;
|
||||
|
||||
@ -296,35 +297,34 @@ static void do_nav_wp()
|
||||
}
|
||||
|
||||
// do_land - initiate landing procedure
|
||||
// caller should set roll_pitch_mode to ROLL_PITCH_AUTO (for no pilot input) or ROLL_PITCH_LOITER (for pilot input)
|
||||
// caller should set yaw_mode
|
||||
static void do_land()
|
||||
{
|
||||
// switch into loiter mode
|
||||
set_nav_mode(NAV_LOITER_ACTIVE);
|
||||
if( ap.home_is_set ) {
|
||||
// switch to loiter if we have gps
|
||||
set_roll_pitch_mode(ROLL_PITCH_LOITER);
|
||||
}else{
|
||||
// otherwise remain with stabilize roll and pitch
|
||||
set_roll_pitch_mode(ROLL_PITCH_STABLE);
|
||||
}
|
||||
|
||||
// hold current heading
|
||||
// hold yaw while landing
|
||||
set_yaw_mode(YAW_HOLD);
|
||||
|
||||
// set throttle mode to land
|
||||
set_throttle_mode(THROTTLE_LAND);
|
||||
|
||||
// switch into loiter nav mode
|
||||
set_nav_mode(NAV_LOITER);
|
||||
}
|
||||
|
||||
// do_loiter_unlimited - start loitering with no end conditions
|
||||
// note: caller should set yaw_mode
|
||||
static void do_loiter_unlimited()
|
||||
{
|
||||
// if no location specified loiter at current location
|
||||
if(command_nav_queue.lat == 0 && command_nav_queue.lng == 0) {
|
||||
set_nav_mode(NAV_LOITER_ACTIVE);
|
||||
}else{
|
||||
// location specified so fly to the target location
|
||||
set_nav_mode(NAV_WP_ACTIVE);
|
||||
#if NAV_WP_ACTIVE == NAV_WP
|
||||
// Set navigation target
|
||||
set_next_WP(&command_nav_queue);
|
||||
#else
|
||||
// Set inav navigation target
|
||||
wpinav_set_destination(command_nav_queue);
|
||||
#endif
|
||||
}
|
||||
// set roll-pitch mode (no pilot input)
|
||||
set_roll_pitch_mode(AUTO_RP);
|
||||
|
||||
// set throttle mode to AUTO which, if not already active, will default to hold at our current altitude
|
||||
set_throttle_mode(THROTTLE_AUTO);
|
||||
@ -333,28 +333,44 @@ static void do_loiter_unlimited()
|
||||
if( command_nav_queue.alt != 0 ) {
|
||||
set_new_altitude(command_nav_queue.alt);
|
||||
}
|
||||
|
||||
// if no location specified loiter at current location
|
||||
if(command_nav_queue.lat == 0 && command_nav_queue.lng == 0) {
|
||||
set_nav_mode(NAV_LOITER);
|
||||
}else{
|
||||
// location specified so fly to the target location
|
||||
set_nav_mode(NAV_WP);
|
||||
// Set inav navigation target
|
||||
wpinav_set_destination(command_nav_queue);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
// do_loiter_turns - initiate moving in a circle
|
||||
static void do_loiter_turns()
|
||||
{
|
||||
// set roll-pitch mode (no pilot input)
|
||||
set_roll_pitch_mode(AUTO_RP);
|
||||
|
||||
// set throttle mode to AUTO which, if not already active, will default to hold at our current altitude
|
||||
set_throttle_mode(THROTTLE_AUTO);
|
||||
|
||||
// set target altitude if provided
|
||||
if( command_nav_queue.alt != 0 ) {
|
||||
set_new_altitude(command_nav_queue.alt);
|
||||
}
|
||||
|
||||
// set nav mode to CIRCLE
|
||||
set_nav_mode(NAV_CIRCLE);
|
||||
|
||||
// set horizontal location target
|
||||
if( command_nav_queue.lat != 0 || command_nav_queue.lng != 0) {
|
||||
set_next_WP_latlon(command_nav_queue.lat, command_nav_queue.lng);
|
||||
}
|
||||
|
||||
// set throttle mode to AUTO which, if not already active, will default to hold at our current altitude
|
||||
set_throttle_mode(THROTTLE_AUTO);
|
||||
|
||||
// set target altitude if provided
|
||||
if( command_nav_queue.alt != 0 ) {
|
||||
set_new_altitude(command_nav_queue.alt);
|
||||
}
|
||||
|
||||
circle_WP = next_WP;
|
||||
yaw_look_at_WP = circle_WP;
|
||||
// set yaw to point to center of circle
|
||||
set_yaw_mode(CIRCLE_YAW);
|
||||
|
||||
loiter_total = command_nav_queue.p1 * 360;
|
||||
loiter_sum = 0;
|
||||
@ -366,32 +382,30 @@ static void do_loiter_turns()
|
||||
}
|
||||
|
||||
// do_loiter_time - initiate loitering at a point for a given time period
|
||||
// note: caller should set yaw_mode
|
||||
static void do_loiter_time()
|
||||
{
|
||||
// if no position specificed loiter at current location
|
||||
if(command_nav_queue.lat == 0 && command_nav_queue.lng == 0) {
|
||||
set_nav_mode(NAV_LOITER_ACTIVE);
|
||||
loiter_time = millis();
|
||||
}else{
|
||||
// location specified so fly to the target location
|
||||
set_nav_mode(NAV_WP_ACTIVE);
|
||||
#if NAV_WP_ACTIVE == NAV_WP
|
||||
// Set navigation target
|
||||
set_next_WP(&command_nav_queue);
|
||||
#else
|
||||
// Set inav navigation target
|
||||
wpinav_set_destination(command_nav_queue);
|
||||
#endif
|
||||
}
|
||||
// set roll-pitch mode (no pilot input)
|
||||
set_roll_pitch_mode(AUTO_RP);
|
||||
|
||||
// set throttle mode to AUTO which, if not already active, will default to hold at our current altitude
|
||||
set_throttle_mode(THROTTLE_AUTO);
|
||||
|
||||
// set target altitude if provided
|
||||
if( command_nav_queue.alt != 0 ) {
|
||||
set_new_altitude(command_nav_queue.alt);
|
||||
}
|
||||
|
||||
// if no position specificed loiter at current location
|
||||
if(command_nav_queue.lat == 0 && command_nav_queue.lng == 0) {
|
||||
set_nav_mode(NAV_LOITER);
|
||||
loiter_time = millis();
|
||||
}else{
|
||||
// location specified so fly to the target location
|
||||
set_nav_mode(NAV_WP);
|
||||
// Set inav navigation target
|
||||
wpinav_set_destination(command_nav_queue);
|
||||
}
|
||||
|
||||
loiter_time_max = command_nav_queue.p1 * 1000; // units are (seconds)
|
||||
}
|
||||
|
||||
@ -404,6 +418,8 @@ static bool verify_takeoff()
|
||||
{
|
||||
// wait until we are ready!
|
||||
if(g.rc_3.control_in == 0) {
|
||||
// To-Do: reset loiter target if we have not yet taken-off
|
||||
// do not allow I term to build up if we have not yet taken-off
|
||||
return false;
|
||||
}
|
||||
// are we above our target altitude?
|
||||
@ -443,7 +459,7 @@ static bool verify_nav_wp()
|
||||
// we have reached our goal
|
||||
|
||||
// loiter at the WP
|
||||
set_nav_mode(NAV_LOITER_ACTIVE);
|
||||
set_nav_mode(NAV_LOITER);
|
||||
|
||||
if ((millis() - loiter_time) > loiter_time_max) {
|
||||
wp_verify_byte |= NAV_DELAY;
|
||||
@ -462,9 +478,9 @@ static bool verify_nav_wp()
|
||||
|
||||
static bool verify_loiter_unlimited()
|
||||
{
|
||||
if(nav_mode == NAV_WP_ACTIVE && wp_distance <= (uint32_t)max((g.waypoint_radius * 100),0)) {
|
||||
if(nav_mode == NAV_WP && wp_distance <= (uint32_t)max((g.waypoint_radius * 100),0)) {
|
||||
// switch to position hold
|
||||
set_nav_mode(NAV_LOITER_ACTIVE);
|
||||
set_nav_mode(NAV_LOITER);
|
||||
}
|
||||
return false;
|
||||
}
|
||||
@ -472,16 +488,16 @@ static bool verify_loiter_unlimited()
|
||||
// verify_loiter_time - check if we have loitered long enough
|
||||
static bool verify_loiter_time()
|
||||
{
|
||||
if(nav_mode == NAV_LOITER_ACTIVE) {
|
||||
if(nav_mode == NAV_LOITER) {
|
||||
if ((millis() - loiter_time) > loiter_time_max) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
if(nav_mode == NAV_WP_ACTIVE && wp_distance <= (uint32_t)max((g.waypoint_radius * 100),0)) {
|
||||
if(nav_mode == NAV_WP && wp_distance <= (uint32_t)max((g.waypoint_radius * 100),0)) {
|
||||
// reset our loiter time
|
||||
loiter_time = millis();
|
||||
// switch to position hold
|
||||
set_nav_mode(NAV_LOITER_ACTIVE);
|
||||
set_nav_mode(NAV_LOITER);
|
||||
}
|
||||
return false;
|
||||
}
|
||||
@ -518,15 +534,9 @@ static bool verify_RTL()
|
||||
set_new_altitude(get_RTL_alt());
|
||||
|
||||
// set navigation mode
|
||||
set_nav_mode(NAV_WP_ACTIVE);
|
||||
|
||||
#if NAV_WP_ACTIVE == NAV_WP
|
||||
// Set navigation target to home
|
||||
set_next_WP(&home);
|
||||
#else
|
||||
set_nav_mode(NAV_WP);
|
||||
// Set inav navigation target to home
|
||||
wpinav_set_destination(home);
|
||||
#endif
|
||||
|
||||
// set yaw mode
|
||||
set_yaw_mode(RTL_YAW);
|
||||
@ -540,7 +550,7 @@ static bool verify_RTL()
|
||||
// if we've reached home initiate loiter
|
||||
if (wp_distance <= (uint32_t)max((g.waypoint_radius * 100),0) || check_missed_wp()) {
|
||||
rtl_state = RTL_STATE_LOITERING_AT_HOME;
|
||||
set_nav_mode(NAV_LOITER_ACTIVE);
|
||||
set_nav_mode(NAV_LOITER);
|
||||
|
||||
// set loiter timer
|
||||
rtl_loiter_start_time = millis();
|
||||
|
@ -75,20 +75,6 @@ static void update_commands()
|
||||
}else{
|
||||
// we have at least one more cmd left
|
||||
Location tmp_loc = get_cmd_with_index(tmp_index);
|
||||
|
||||
if(tmp_loc.lat == 0) {
|
||||
ap.fast_corner = false;
|
||||
}else{
|
||||
int32_t temp = get_bearing_cd(&next_WP, &tmp_loc) - original_wp_bearing;
|
||||
temp = wrap_180(temp);
|
||||
ap.fast_corner = labs(temp) < 6000;
|
||||
}
|
||||
|
||||
// If we try and stop at a corner, lets reset our desired speed to prevent
|
||||
// too much jerkyness.
|
||||
if(false == ap.fast_corner){
|
||||
reset_desired_speed();
|
||||
}
|
||||
}
|
||||
|
||||
}else{
|
||||
|
@ -607,14 +607,6 @@
|
||||
#define EARTH_FRAME 0
|
||||
#define BODY_FRAME 1
|
||||
|
||||
// active NAV controller
|
||||
#ifndef NAV_WP_ACTIVE
|
||||
# define NAV_WP_ACTIVE NAV_WP
|
||||
#endif
|
||||
// active LOITER controller
|
||||
#ifndef NAV_LOITER_ACTIVE
|
||||
# define NAV_LOITER_ACTIVE NAV_LOITER
|
||||
#endif
|
||||
|
||||
// Flight mode roll, pitch, yaw, throttle and navigation definitions
|
||||
|
||||
@ -631,10 +623,6 @@
|
||||
# define ACRO_THR THROTTLE_MANUAL
|
||||
#endif
|
||||
|
||||
#ifndef ACRO_NAV
|
||||
# define ACRO_NAV NAV_NONE
|
||||
#endif
|
||||
|
||||
// Alt Hold Mode
|
||||
#ifndef ALT_HOLD_YAW
|
||||
# define ALT_HOLD_YAW YAW_HOLD
|
||||
@ -648,10 +636,6 @@
|
||||
# define ALT_HOLD_THR THROTTLE_HOLD
|
||||
#endif
|
||||
|
||||
#ifndef ALT_HOLD_NAV
|
||||
# define ALT_HOLD_NAV NAV_NONE
|
||||
#endif
|
||||
|
||||
// AUTO Mode
|
||||
#ifndef AUTO_YAW
|
||||
# define AUTO_YAW YAW_LOOK_AT_NEXT_WP
|
||||
@ -705,7 +689,7 @@
|
||||
#endif
|
||||
|
||||
#ifndef LOITER_RP
|
||||
# define LOITER_RP ROLL_PITCH_AUTO
|
||||
# define LOITER_RP ROLL_PITCH_LOITER
|
||||
#endif
|
||||
|
||||
#ifndef LOITER_THR
|
||||
@ -713,7 +697,7 @@
|
||||
#endif
|
||||
|
||||
#ifndef LOITER_NAV
|
||||
# define LOITER_NAV NAV_LOITER_ACTIVE
|
||||
# define LOITER_NAV NAV_LOITER
|
||||
#endif
|
||||
|
||||
// POSITION Mode
|
||||
@ -730,7 +714,7 @@
|
||||
#endif
|
||||
|
||||
#ifndef POSITION_NAV
|
||||
# define POSITION_NAV NAV_LOITER_ACTIVE
|
||||
# define POSITION_NAV NAV_LOITER
|
||||
#endif
|
||||
|
||||
|
||||
@ -1277,9 +1261,4 @@
|
||||
# define SECONDARY_DMP_ENABLED DISABLED
|
||||
#endif
|
||||
|
||||
// Inertia based contollers.
|
||||
#ifndef INERTIAL_NAV_XY
|
||||
# define INERTIAL_NAV_XY DISABLED
|
||||
#endif
|
||||
|
||||
#endif // __ARDUCOPTER_CONFIG_H__
|
||||
|
@ -25,13 +25,12 @@
|
||||
#define YAW_TOY 7 // THOR This is the Yaw mode
|
||||
|
||||
|
||||
#define ROLL_PITCH_STABLE 0
|
||||
#define ROLL_PITCH_ACRO 1
|
||||
#define ROLL_PITCH_AUTO 2
|
||||
#define ROLL_PITCH_STABLE_OF 3
|
||||
#define ROLL_PITCH_STABLE 0 // pilot input roll, pitch angles
|
||||
#define ROLL_PITCH_ACRO 1 // pilot inputs roll, pitch rotation rates
|
||||
#define ROLL_PITCH_AUTO 2 // no pilot input. autopilot roll, pitch is sent to stabilize controller inputs
|
||||
#define ROLL_PITCH_STABLE_OF 3 // pilot inputs roll, pitch angles which are mixed with optical flow based position controller lean anbles
|
||||
#define ROLL_PITCH_TOY 4 // THOR This is the Roll and Pitch mode
|
||||
#define ROLL_PITCH_LOITER_INAV 5 // pilot inputs the desired horizontal velocities
|
||||
#define ROLL_PITCH_WP_INAV 6 // pilot inputs the desired horizontal velocities which temporarily interrupt the autopilot
|
||||
#define ROLL_PITCH_LOITER 5 // pilot inputs the desired horizontal velocities
|
||||
|
||||
#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
|
||||
@ -200,7 +199,6 @@
|
||||
#define NAV_CIRCLE 1
|
||||
#define NAV_LOITER 2
|
||||
#define NAV_WP 3
|
||||
#define NAV_LOITER_INAV 4
|
||||
#define NAV_WP_INAV 5
|
||||
|
||||
// Yaw override behaviours - used for setting yaw_override_behaviour
|
||||
|
@ -1,77 +1,31 @@
|
||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
// update_navigation - checks for new GPS updates and invokes navigation routines
|
||||
// update_navigation - invokes navigation routines
|
||||
// called at 50hz
|
||||
static void update_navigation()
|
||||
{
|
||||
static uint32_t nav_last_update = 0; // the system time of the last time nav was run update
|
||||
bool pos_updated = false;
|
||||
bool log_output = false;
|
||||
|
||||
#if INERTIAL_NAV_XY == ENABLED
|
||||
static uint8_t nav_counter = 0; // used to slow down the navigation to 10hz
|
||||
|
||||
// check for inertial nav updates
|
||||
if( inertial_nav.position_ok() ) {
|
||||
nav_counter++;
|
||||
if( nav_counter >= 5) {
|
||||
nav_counter = 0;
|
||||
|
||||
// calculate time since nav controllers last ran
|
||||
dTnav = (float)(millis() - nav_last_update)/ 1000.0f;
|
||||
nav_last_update = millis();
|
||||
|
||||
// prevent runnup in dTnav value
|
||||
dTnav = min(dTnav, 1.0f);
|
||||
|
||||
// signal to run nav controllers
|
||||
pos_updated = true;
|
||||
|
||||
// signal to create log entry
|
||||
log_output = true;
|
||||
}
|
||||
}
|
||||
#else
|
||||
|
||||
static uint32_t nav_last_gps_time = 0; // the time according to the gps
|
||||
|
||||
// check for new gps data
|
||||
if( g_gps->fix && g_gps->time != nav_last_gps_time ) {
|
||||
|
||||
// used to calculate speed in X and Y, iterms
|
||||
// ------------------------------------------
|
||||
// calculate time since nav controllers last ran
|
||||
dTnav = (float)(millis() - nav_last_update)/ 1000.0f;
|
||||
nav_last_update = millis();
|
||||
|
||||
// prevent runup from bad GPS
|
||||
// prevent runnup in dTnav value
|
||||
dTnav = min(dTnav, 1.0f);
|
||||
|
||||
// save GPS time
|
||||
nav_last_gps_time = g_gps->time;
|
||||
|
||||
// signal to run nav controllers
|
||||
pos_updated = true;
|
||||
|
||||
// signal to create log entry
|
||||
log_output = true;
|
||||
}
|
||||
#endif
|
||||
|
||||
// setup to calculate new navigation values and run controllers if
|
||||
// we've received a position update
|
||||
if( pos_updated ) {
|
||||
|
||||
nav_updates.need_velpos = 1;
|
||||
nav_updates.need_dist_bearing = 1;
|
||||
nav_updates.need_nav_controllers = 1;
|
||||
nav_updates.need_nav_pitch_roll = 1;
|
||||
// run the navigation controllers
|
||||
update_nav_mode();
|
||||
|
||||
// update log
|
||||
if (log_output && (g.log_bitmask & MASK_LOG_NTUN) && motors.armed()) {
|
||||
if (g.log_bitmask & MASK_LOG_NTUN && motors.armed()) {
|
||||
Log_Write_Nav_Tuning();
|
||||
}
|
||||
}
|
||||
|
||||
// To-Do: replace below with proper GPS failsafe
|
||||
// reduce nav outputs to zero if we have not seen a position update in 2 seconds
|
||||
if( millis() - nav_last_update > 2000 ) {
|
||||
// after 12 reads we guess we may have lost GPS signal, stop navigating
|
||||
@ -81,95 +35,68 @@ static void update_navigation()
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
run navigation updates from nav_updates. Only run one at a time to
|
||||
prevent too much cpu usage hurting the main loop
|
||||
*/
|
||||
// run_nav_updates - top level call for the autopilot
|
||||
// ensures calculations such as "distance to waypoint" are calculated before autopilot makes decisions
|
||||
// To-Do - rename and move this function to make it's purpose more clear
|
||||
static void run_nav_updates(void)
|
||||
{
|
||||
if (nav_updates.need_velpos) {
|
||||
calc_velocity_and_position();
|
||||
verify_altitude();
|
||||
nav_updates.need_velpos = 0;
|
||||
} else if (nav_updates.need_dist_bearing) {
|
||||
calc_distance_and_bearing();
|
||||
nav_updates.need_dist_bearing = 0;
|
||||
} else if (nav_updates.need_nav_controllers) {
|
||||
run_autopilot();
|
||||
update_nav_mode();
|
||||
nav_updates.need_nav_controllers = 0;
|
||||
} else if (nav_updates.need_nav_pitch_roll) {
|
||||
calc_nav_pitch_roll();
|
||||
nav_updates.need_nav_pitch_roll = 0;
|
||||
}
|
||||
// fetch position from inertial navigation
|
||||
calc_position();
|
||||
|
||||
// check altitude vs target
|
||||
verify_altitude();
|
||||
|
||||
// calculate distance and bearing for reporting and autopilot decisions
|
||||
calc_distance_and_bearing();
|
||||
|
||||
// run autopilot to make high level decisions about control modes
|
||||
run_autopilot();
|
||||
}
|
||||
|
||||
|
||||
//*******************************************************************************************************
|
||||
// calc_velocity_and_filtered_position - velocity in lon and lat directions calculated from GPS position
|
||||
// and accelerometer data
|
||||
// lon_speed expressed in cm/s. positive numbers mean moving east
|
||||
// lat_speed expressed in cm/s. positive numbers when moving north
|
||||
// Note: we use gps locations directly to calculate velocity instead of asking gps for velocity because
|
||||
// this is more accurate below 1.5m/s
|
||||
// Note: even though the positions are projected using a lead filter, the velocities are calculated
|
||||
// from the unaltered gps locations. We do not want noise from our lead filter affecting velocity
|
||||
//*******************************************************************************************************
|
||||
static void calc_velocity_and_position(){
|
||||
#if INERTIAL_NAV_XY == ENABLED
|
||||
// calc_position - get lat and lon positions from inertial nav library
|
||||
static void calc_position(){
|
||||
if( inertial_nav.position_ok() ) {
|
||||
// pull velocity from interial nav library
|
||||
lon_speed = inertial_nav.get_longitude_velocity();
|
||||
lat_speed = inertial_nav.get_latitude_velocity();
|
||||
|
||||
// pull position from interial nav library
|
||||
current_loc.lng = inertial_nav.get_longitude();
|
||||
current_loc.lat = inertial_nav.get_latitude();
|
||||
}
|
||||
#else
|
||||
static int32_t last_gps_longitude = 0;
|
||||
static int32_t last_gps_latitude = 0;
|
||||
|
||||
// initialise last_longitude and last_latitude
|
||||
if( last_gps_longitude == 0 && last_gps_latitude == 0 ) {
|
||||
last_gps_longitude = g_gps->longitude;
|
||||
last_gps_latitude = g_gps->latitude;
|
||||
}
|
||||
|
||||
// this speed is ~ in cm because we are using 10^7 numbers from GPS
|
||||
float tmp = 1.0f/dTnav;
|
||||
|
||||
// calculate velocity
|
||||
lon_speed = (float)(g_gps->longitude - last_gps_longitude) * scaleLongDown * tmp;
|
||||
lat_speed = (float)(g_gps->latitude - last_gps_latitude) * tmp;
|
||||
|
||||
// calculate position from gps + expected travel during gps_lag
|
||||
current_loc.lng = xLeadFilter.get_position(g_gps->longitude, lon_speed, g_gps->get_lag());
|
||||
current_loc.lat = yLeadFilter.get_position(g_gps->latitude, lat_speed, g_gps->get_lag());
|
||||
|
||||
// store gps lat and lon values for next iteration
|
||||
last_gps_longitude = g_gps->longitude;
|
||||
last_gps_latitude = g_gps->latitude;
|
||||
#endif
|
||||
}
|
||||
|
||||
//****************************************************************
|
||||
// Function that will calculate the desired direction to fly and distance
|
||||
//****************************************************************
|
||||
// calc_distance_and_bearing - calculate distance and direction to waypoints for reporting and autopilot decisions
|
||||
static void calc_distance_and_bearing()
|
||||
{
|
||||
// waypoint distance (in cm) and bearaing from plane
|
||||
// get current position
|
||||
Vector2f curr_pos(inertial_nav.get_latitude_diff(), inertial_nav.get_longitude_diff());
|
||||
Vector2f dest;
|
||||
|
||||
// get target from loiter or wpinav controller
|
||||
if( nav_mode == NAV_LOITER || nav_mode == NAV_CIRCLE ) {
|
||||
dest.x = loiter_lat_from_home_cm;
|
||||
dest.y = loiter_lon_from_home_cm;
|
||||
}else if( nav_mode == NAV_WP ) {
|
||||
dest.x = wpinav_destination.x;
|
||||
dest.y = wpinav_destination.y;
|
||||
}else{
|
||||
dest = curr_pos;
|
||||
}
|
||||
|
||||
// calculate distance to target
|
||||
lat_error = dest.x - curr_pos.x;
|
||||
lon_error = dest.y - curr_pos.y;
|
||||
wp_distance = safe_sqrt(lat_error*lat_error+lon_error*lon_error);
|
||||
|
||||
// calculate waypoint bearing
|
||||
// To-Do: change this to more efficient calculation
|
||||
if( waypoint_valid(next_WP) ) {
|
||||
wp_distance = get_distance_cm(¤t_loc, &next_WP);
|
||||
wp_bearing = get_bearing_cd(¤t_loc, &next_WP);
|
||||
}else{
|
||||
wp_distance = 0;
|
||||
wp_bearing = 0;
|
||||
}
|
||||
|
||||
// calculate home distance and bearing
|
||||
if( ap.home_is_set ) {
|
||||
home_distance = get_distance_cm(¤t_loc, &home);
|
||||
home_distance = safe_sqrt(curr_pos.x*curr_pos.x + curr_pos.y*curr_pos.y);
|
||||
// To-Do: change this to more efficient calculation
|
||||
home_bearing = get_bearing_cd(¤t_loc, &home);
|
||||
|
||||
// update super simple bearing (if required) because it relies on home_bearing
|
||||
@ -177,32 +104,15 @@ static void calc_distance_and_bearing()
|
||||
}else{
|
||||
home_distance = 0;
|
||||
home_bearing = 0;
|
||||
}
|
||||
}
|
||||
|
||||
// calculate bearing to target (used when yaw_mode = YAW_LOOK_AT_LOCATION)
|
||||
// To-Do: move this to the look-at-waypoint yaw controller
|
||||
if( waypoint_valid(yaw_look_at_WP) ) {
|
||||
yaw_look_at_WP_bearing = get_bearing_cd(¤t_loc, &yaw_look_at_WP);
|
||||
}
|
||||
}
|
||||
|
||||
static void calc_location_error(struct Location *next_loc)
|
||||
{
|
||||
/*
|
||||
* Becuase we are using lat and lon to do our distance errors here's a quick chart:
|
||||
* 100 = 1m
|
||||
* 1000 = 11m = 36 feet
|
||||
* 1800 = 19.80m = 60 feet
|
||||
* 3000 = 33m
|
||||
* 10000 = 111m
|
||||
*/
|
||||
|
||||
// X Error
|
||||
long_error = (float)(next_loc->lng - current_loc.lng) * scaleLongDown; // 500 - 0 = 500 Go East
|
||||
|
||||
// Y Error
|
||||
lat_error = next_loc->lat - current_loc.lat; // 500 - 0 = 500 Go North
|
||||
}
|
||||
|
||||
// run_autopilot - highest level call to process mission commands
|
||||
static void run_autopilot()
|
||||
{
|
||||
@ -214,7 +124,7 @@ static void run_autopilot()
|
||||
case GUIDED:
|
||||
// switch to loiter once we've reached the target location and altitude
|
||||
if(verify_nav_wp()) {
|
||||
set_nav_mode(NAV_LOITER_ACTIVE);
|
||||
set_nav_mode(NAV_LOITER);
|
||||
}
|
||||
case RTL:
|
||||
verify_RTL();
|
||||
@ -249,24 +159,13 @@ static bool set_nav_mode(uint8_t new_nav_mode)
|
||||
|
||||
case NAV_LOITER:
|
||||
// set target to current position
|
||||
set_next_WP_latlon(current_loc.lat, current_loc.lng);
|
||||
loiter_set_target(inertial_nav.get_latitude_diff(), inertial_nav.get_longitude_diff());
|
||||
nav_initialised = true;
|
||||
break;
|
||||
|
||||
case NAV_WP:
|
||||
nav_initialised = true;
|
||||
break;
|
||||
|
||||
case NAV_LOITER_INAV:
|
||||
loiter_set_target(inertial_nav.get_latitude_diff(), inertial_nav.get_longitude_diff());
|
||||
// To-Do: below allows user to move around set point but do we want to allow this when in Auto flight mode?
|
||||
nav_initialised = set_roll_pitch_mode(ROLL_PITCH_LOITER_INAV);
|
||||
break;
|
||||
|
||||
case NAV_WP_INAV:
|
||||
// To-Do: below allows user to move around set point but do we want to allow this when in Auto flight mode?
|
||||
nav_initialised = set_roll_pitch_mode(ROLL_PITCH_WP_INAV);
|
||||
break;
|
||||
}
|
||||
|
||||
// if initialisation has been successful update the yaw mode
|
||||
@ -282,7 +181,6 @@ static bool set_nav_mode(uint8_t new_nav_mode)
|
||||
static void update_nav_mode()
|
||||
{
|
||||
int16_t loiter_delta;
|
||||
int16_t speed;
|
||||
|
||||
switch( nav_mode ) {
|
||||
|
||||
@ -306,8 +204,6 @@ static void update_nav_mode()
|
||||
|
||||
circle_angle += (circle_rate * dTnav);
|
||||
|
||||
//1 degree = 0.0174532925 radians
|
||||
|
||||
// wrap
|
||||
if (circle_angle > 6.28318531f)
|
||||
circle_angle -= 6.28318531f;
|
||||
@ -317,63 +213,13 @@ static void update_nav_mode()
|
||||
set_next_WP_latlon(
|
||||
circle_WP.lat + (g.circle_radius * 100 * sinf(1.57f - circle_angle)),
|
||||
circle_WP.lng + (g.circle_radius * 100 * cosf(1.57f - circle_angle) * scaleLongUp));
|
||||
|
||||
// use error as the desired rate towards the target
|
||||
// nav_lon, nav_lat is calculated
|
||||
|
||||
// if the target location is >4m use waypoint controller
|
||||
if(wp_distance > 400) {
|
||||
calc_nav_rate(get_desired_speed(g.waypoint_speed_max));
|
||||
}else{
|
||||
// calc the lat and long error to the target
|
||||
calc_location_error(&next_WP);
|
||||
// call loiter controller
|
||||
calc_loiter(long_error, lat_error);
|
||||
}
|
||||
break;
|
||||
|
||||
case NAV_LOITER:
|
||||
// check if user is overriding the loiter controller
|
||||
if((abs(g.rc_2.control_in) + abs(g.rc_1.control_in)) > 500) {
|
||||
if(wp_distance > 500){
|
||||
ap.loiter_override = true;
|
||||
}
|
||||
}
|
||||
|
||||
// check if user has release sticks
|
||||
if(ap.loiter_override) {
|
||||
if(g.rc_2.control_in == 0 && g.rc_1.control_in == 0) {
|
||||
ap.loiter_override = false;
|
||||
// reset LOITER to current position
|
||||
set_next_WP_latlon(current_loc.lat, current_loc.lng);
|
||||
}
|
||||
// We bring copy over our Iterms for wind control, but we don't navigate
|
||||
nav_lon = g.pid_loiter_rate_lon.get_integrator();
|
||||
nav_lat = g.pid_loiter_rate_lon.get_integrator();
|
||||
nav_lon = constrain(nav_lon, -2000, 2000);
|
||||
nav_lat = constrain(nav_lat, -2000, 2000);
|
||||
}else{
|
||||
// calc error to target
|
||||
calc_location_error(&next_WP);
|
||||
// use error as the desired rate towards the target
|
||||
calc_loiter(long_error, lat_error);
|
||||
}
|
||||
break;
|
||||
|
||||
case NAV_WP:
|
||||
// calc position error to target
|
||||
calc_location_error(&next_WP);
|
||||
// calc speed to target
|
||||
speed = get_desired_speed(g.waypoint_speed_max);
|
||||
// use error as the desired rate towards the target
|
||||
calc_nav_rate(speed);
|
||||
break;
|
||||
|
||||
case NAV_LOITER_INAV:
|
||||
get_loiter_pos_lat_lon(loiter_lat_from_home_cm, loiter_lon_from_home_cm, 0.1f);
|
||||
break;
|
||||
|
||||
case NAV_WP_INAV:
|
||||
case NAV_WP:
|
||||
// move forward on the waypoint
|
||||
// To-Do: slew up the speed to the max waypoint speed instead of immediately jumping to max
|
||||
wpinav_advance_track_desired(g.waypoint_speed_max, 0.1f);
|
||||
@ -401,207 +247,6 @@ static bool check_missed_wp()
|
||||
return (labs(temp) > 9000); // we passed the waypoint by 90 degrees
|
||||
}
|
||||
|
||||
////////////////////////////////////////////////////////////////
|
||||
// Loiter controller (based on GPS position)
|
||||
////////////////////////////////////////////////////////////////
|
||||
#define NAV_ERR_MAX 600
|
||||
#define NAV_RATE_ERR_MAX 250
|
||||
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 + x_error, dTnav);
|
||||
d = g.pid_loiter_rate_lon.get_d(x_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, -4500, 4500); // constrain max angle to 45 degrees
|
||||
|
||||
#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 + y_error, dTnav);
|
||||
d = g.pid_loiter_rate_lat.get_d(y_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, -4500, 4500); // constrain max angle to 45 degrees
|
||||
|
||||
#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());
|
||||
}
|
||||
|
||||
///////////////////////////////////////////////////////////
|
||||
// Waypoint controller (based on GPS position)
|
||||
///////////////////////////////////////////////////////////
|
||||
static void calc_nav_rate(int16_t max_speed)
|
||||
{
|
||||
float temp, temp_x, temp_y;
|
||||
|
||||
// push us towards the original track
|
||||
update_crosstrack();
|
||||
|
||||
int16_t cross_speed = crosstrack_error * -g.crosstrack_gain; // scale down crosstrack_error in cm
|
||||
cross_speed = constrain(cross_speed, -150, 150);
|
||||
|
||||
// rotate by 90 to deal with trig functions
|
||||
temp = (9000l - wp_bearing) * RADX100;
|
||||
temp_x = cosf(temp);
|
||||
temp_y = sinf(temp);
|
||||
|
||||
// rotate desired spped vector:
|
||||
int32_t x_target_speed = max_speed * temp_x - cross_speed * temp_y;
|
||||
int32_t y_target_speed = cross_speed * temp_x + max_speed * temp_y;
|
||||
|
||||
// East / West
|
||||
// calculate rate error
|
||||
x_rate_error = x_target_speed - lon_speed;
|
||||
|
||||
x_rate_error = constrain(x_rate_error, -500, 500);
|
||||
nav_lon = g.pid_nav_lon.get_pid(x_rate_error, dTnav);
|
||||
int32_t tilt = (x_target_speed * x_target_speed * (int32_t)g.tilt_comp) / 10000;
|
||||
|
||||
if(x_target_speed < 0) tilt = -tilt;
|
||||
nav_lon += tilt;
|
||||
|
||||
|
||||
// North / South
|
||||
// calculate rate error
|
||||
y_rate_error = y_target_speed - lat_speed;
|
||||
|
||||
y_rate_error = constrain(y_rate_error, -500, 500); // added a rate error limit to keep pitching down to a minimum
|
||||
nav_lat = g.pid_nav_lat.get_pid(y_rate_error, dTnav);
|
||||
tilt = (y_target_speed * y_target_speed * (int32_t)g.tilt_comp) / 10000;
|
||||
|
||||
if(y_target_speed < 0) tilt = -tilt;
|
||||
nav_lat += tilt;
|
||||
|
||||
// copy over I term to Loiter_Rate
|
||||
g.pid_loiter_rate_lon.set_integrator(g.pid_nav_lon.get_integrator());
|
||||
g.pid_loiter_rate_lat.set_integrator(g.pid_nav_lat.get_integrator());
|
||||
}
|
||||
|
||||
|
||||
// this calculation rotates our World frame of reference to the copter's frame of reference
|
||||
// We use the DCM's matrix to precalculate these trig values at 50hz
|
||||
static void calc_nav_pitch_roll()
|
||||
{
|
||||
// To-Do: remove this hack dependent upon nav_mode
|
||||
if( nav_mode != NAV_LOITER_INAV && nav_mode != NAV_WP_INAV ) {
|
||||
// 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;
|
||||
|
||||
// flip pitch because forward is negative
|
||||
auto_pitch = -auto_pitch;
|
||||
|
||||
// constrain maximum roll and pitch angles to 45 degrees
|
||||
auto_roll = constrain(auto_roll, -4500, 4500);
|
||||
auto_pitch = constrain(auto_pitch, -4500, 4500);
|
||||
}
|
||||
}
|
||||
|
||||
static int16_t get_desired_speed(int16_t max_speed)
|
||||
{
|
||||
/*
|
||||
Based on Equation by Bill Premerlani & Robert Lefebvre
|
||||
(sq(V2)-sq(V1))/2 = A(X2-X1)
|
||||
derives to:
|
||||
V1 = sqrt(sq(V2) - 2*A*(X2-X1))
|
||||
*/
|
||||
|
||||
if(ap.fast_corner) {
|
||||
// don't slow down
|
||||
}else{
|
||||
if(wp_distance < 20000){ // limit the size of numbers we're dealing with to avoid overflow
|
||||
// go slower
|
||||
int32_t temp = 2 * 100 * (int32_t)(wp_distance - g.waypoint_radius * 100);
|
||||
int32_t s_min = WAYPOINT_SPEED_MIN;
|
||||
temp += s_min * s_min;
|
||||
if( temp < 0 ) temp = 0; // check to ensure we don't try to take the sqrt of a negative number
|
||||
max_speed = sqrtf((float)temp);
|
||||
max_speed = min(max_speed, g.waypoint_speed_max);
|
||||
}
|
||||
}
|
||||
|
||||
max_speed = min(max_speed, max_speed_old + (100 * dTnav));// limit going faster
|
||||
max_speed = max(max_speed, WAYPOINT_SPEED_MIN); // don't go too slow
|
||||
max_speed_old = max_speed;
|
||||
return max_speed;
|
||||
}
|
||||
|
||||
static void reset_desired_speed()
|
||||
{
|
||||
max_speed_old = 0;
|
||||
}
|
||||
|
||||
static void update_crosstrack(void)
|
||||
{
|
||||
// Crosstrack Error
|
||||
// ----------------
|
||||
if (wp_distance >= (unsigned long)max((g.crosstrack_min_distance * 100),0) &&
|
||||
abs(wrap_180(wp_bearing - original_wp_bearing)) < 4500) {
|
||||
|
||||
float temp = (wp_bearing - original_wp_bearing) * RADX100;
|
||||
crosstrack_error = sinf(temp) * wp_distance; // Meters we are off track line
|
||||
}else{
|
||||
// fade out crosstrack
|
||||
crosstrack_error >>= 1;
|
||||
}
|
||||
}
|
||||
|
||||
static void force_new_altitude(int32_t new_alt)
|
||||
{
|
||||
next_WP.alt = new_alt;
|
||||
@ -632,6 +277,7 @@ static void set_new_altitude(int32_t new_alt)
|
||||
}
|
||||
}
|
||||
|
||||
// verify_altitude - check if we have reached the target altitude
|
||||
static void verify_altitude()
|
||||
{
|
||||
if(alt_change_flag == ASCENDING) {
|
||||
@ -662,8 +308,8 @@ static void reset_nav_params(void)
|
||||
// Will be set by new command
|
||||
wp_distance = 0;
|
||||
|
||||
// Will be set by new command, used by loiter
|
||||
long_error = 0;
|
||||
// Will be set by nav or loiter controllers
|
||||
lon_error = 0;
|
||||
lat_error = 0;
|
||||
nav_lon = 0;
|
||||
nav_lat = 0;
|
||||
|
@ -387,11 +387,6 @@ static void set_mode(uint8_t mode)
|
||||
// if we change modes, we must clear landed flag
|
||||
set_land_complete(false);
|
||||
|
||||
// debug to Serial terminal
|
||||
//cliSerial->println(flight_mode_strings[control_mode]);
|
||||
|
||||
ap.loiter_override = false;
|
||||
|
||||
// report the GPS and Motor arming status
|
||||
led_mode = NORMAL_LEDS;
|
||||
|
||||
@ -403,7 +398,7 @@ static void set_mode(uint8_t mode)
|
||||
set_yaw_mode(ACRO_YAW);
|
||||
set_roll_pitch_mode(ACRO_RP);
|
||||
set_throttle_mode(ACRO_THR);
|
||||
set_nav_mode(ACRO_NAV);
|
||||
set_nav_mode(NAV_NONE);
|
||||
// reset acro axis targets to current attitude
|
||||
if(g.axis_enabled){
|
||||
roll_axis = ahrs.roll_sensor;
|
||||
@ -427,7 +422,7 @@ static void set_mode(uint8_t mode)
|
||||
set_yaw_mode(ALT_HOLD_YAW);
|
||||
set_roll_pitch_mode(ALT_HOLD_RP);
|
||||
set_throttle_mode(ALT_HOLD_THR);
|
||||
set_nav_mode(ALT_HOLD_NAV);
|
||||
set_nav_mode(NAV_NONE);
|
||||
break;
|
||||
|
||||
case AUTO:
|
||||
@ -484,16 +479,13 @@ static void set_mode(uint8_t mode)
|
||||
break;
|
||||
|
||||
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
|
||||
if( ap.home_is_set ) {
|
||||
// switch to loiter if we have gps
|
||||
ap.manual_attitude = false;
|
||||
set_yaw_mode(LOITER_YAW);
|
||||
set_roll_pitch_mode(LOITER_RP);
|
||||
}else{
|
||||
// otherwise remain with stabilize roll and pitch
|
||||
ap.manual_attitude = true;
|
||||
set_yaw_mode(YAW_HOLD);
|
||||
set_roll_pitch_mode(ROLL_PITCH_STABLE);
|
||||
}
|
||||
ap.manual_throttle = false;
|
||||
do_land();
|
||||
|
Loading…
Reference in New Issue
Block a user