/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * control_guided.pde - init and run calls for guided flight mode */ #ifndef GUIDED_LOOK_AT_TARGET_MIN_DISTANCE_CM # define GUIDED_LOOK_AT_TARGET_MIN_DISTANCE_CM 500 // point nose at target if it is more than 5m away #endif #define GUIDED_POSVEL_TIMEOUT_MS 3000 // guided mode's position-velocity controller times out after 3seconds with no new updates static Vector3f posvel_pos_target_cm; static Vector3f posvel_vel_target_cms; static uint32_t posvel_update_time_ms; struct Guided_Limit { uint32_t timeout_ms; // timeout (in seconds) from the time that guided is invoked float alt_min_cm; // lower altitude limit in cm above home (0 = no limit) float alt_max_cm; // upper altitude limit in cm above home (0 = no limit) float horiz_max_cm; // horizontal position limit in cm from where guided mode was initiated (0 = no limit) uint32_t start_time;// system time in milliseconds that control was handed to the external computer Vector3f start_pos; // start position as a distance from home in cm. used for checking horiz_max limit } guided_limit; // guided_init - initialise guided controller static bool guided_init(bool ignore_checks) { if (position_ok() || ignore_checks) { // initialise yaw set_auto_yaw_mode(get_default_auto_yaw_mode(false)); // start in position control mode guided_pos_control_start(); return true; }else{ return false; } } // guided_takeoff_start - initialises waypoint controller to implement take-off static void guided_takeoff_start(float final_alt) { guided_mode = Guided_TakeOff; // initialise wpnav destination Vector3f target_pos = inertial_nav.get_position(); target_pos.z = final_alt; wp_nav.set_wp_destination(target_pos); // initialise yaw set_auto_yaw_mode(AUTO_YAW_HOLD); // tell motors to do a slow start motors.slow_start(true); } // initialise guided mode's position controller static void guided_pos_control_start() { // set to position control mode guided_mode = Guided_WP; // initialise waypoint and spline controller wp_nav.wp_and_spline_init(); // initialise wpnav to stopping point at current altitude // To-Do: set to current location if disarmed? // To-Do: set to stopping point altitude? Vector3f stopping_point; stopping_point.z = inertial_nav.get_altitude(); wp_nav.get_wp_stopping_point_xy(stopping_point); wp_nav.set_wp_destination(stopping_point); // initialise yaw set_auto_yaw_mode(get_default_auto_yaw_mode(false)); } // initialise guided mode's velocity controller static void guided_vel_control_start() { // set guided_mode to velocity controller guided_mode = Guided_Velocity; // initialize vertical speeds and leash lengths pos_control.set_speed_z(-g.pilot_velocity_z_max, g.pilot_velocity_z_max); pos_control.set_accel_z(g.pilot_accel_z); // initialise velocity controller pos_control.init_vel_controller_xyz(); } // initialise guided mode's posvel controller static void guided_posvel_control_start() { // set guided_mode to velocity controller guided_mode = Guided_PosVel; pos_control.init_xy_controller(); // set speed and acceleration from wpnav's speed and acceleration pos_control.set_speed_xy(wp_nav.get_speed_xy()); pos_control.set_accel_xy(wp_nav.get_wp_acceleration()); const Vector3f& curr_pos = inertial_nav.get_position(); const Vector3f& curr_vel = inertial_nav.get_velocity(); // set target position and velocity to current position and velocity pos_control.set_xy_target(curr_pos.x, curr_pos.y); pos_control.set_desired_velocity_xy(curr_vel.x, curr_vel.y); // set vertical speed and acceleration pos_control.set_speed_z(wp_nav.get_speed_down(), wp_nav.get_speed_up()); pos_control.set_accel_z(wp_nav.get_accel_z()); // pilot always controls yaw set_auto_yaw_mode(AUTO_YAW_HOLD); } // guided_set_destination - sets guided mode's target destination static void guided_set_destination(const Vector3f& destination) { // ensure we are in position control mode if (guided_mode != Guided_WP) { guided_pos_control_start(); } wp_nav.set_wp_destination(destination); } // guided_set_velocity - sets guided mode's target velocity static void guided_set_velocity(const Vector3f& velocity) { // check we are in velocity control mode if (guided_mode != Guided_Velocity) { guided_vel_control_start(); } // set position controller velocity target pos_control.set_desired_velocity(velocity); } // set guided mode posvel target static void guided_set_destination_posvel(const Vector3f& destination, const Vector3f& velocity) { // check we are in velocity control mode if (guided_mode != Guided_PosVel) { guided_posvel_control_start(); } posvel_update_time_ms = millis(); posvel_pos_target_cm = destination; posvel_vel_target_cms = velocity; pos_control.set_pos_target(posvel_pos_target_cm); } // guided_run - runs the guided controller // should be called at 100hz or more static void guided_run() { // if not auto armed set throttle to zero and exit immediately if(!ap.auto_armed) { // To-Do: reset waypoint controller? attitude_control.relax_bf_rate_controller(); attitude_control.set_yaw_target_to_current_heading(); attitude_control.set_throttle_out(0, false); // To-Do: handle take-offs - these may not only be immediately after auto_armed becomes true return; } // call the correct auto controller switch (guided_mode) { case Guided_TakeOff: // run takeoff controller guided_takeoff_run(); break; case Guided_WP: // run position controller guided_pos_control_run(); break; case Guided_Velocity: // run velocity controller guided_vel_control_run(); break; case Guided_PosVel: // run position-velocity controller guided_posvel_control_run(); break; } } // guided_takeoff_run - takeoff in guided mode // called by guided_run at 100hz or more static void guided_takeoff_run() { // if not auto armed set throttle to zero and exit immediately if(!ap.auto_armed) { // initialise wpnav targets wp_nav.shift_wp_origin_to_current_pos(); // reset attitude control targets attitude_control.relax_bf_rate_controller(); attitude_control.set_yaw_target_to_current_heading(); attitude_control.set_throttle_out(0, false); // tell motors to do a slow start motors.slow_start(true); return; } // process pilot's yaw input float target_yaw_rate = 0; if (!failsafe.radio) { // get pilot's desired yaw rate target_yaw_rate = get_pilot_desired_yaw_rate(g.rc_4.control_in); } // run waypoint controller wp_nav.update_wpnav(); // call z-axis position controller (wpnav should have already updated it's alt target) pos_control.update_z_controller(); // roll & pitch from waypoint controller, yaw rate from pilot attitude_control.angle_ef_roll_pitch_rate_ef_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate); } // guided_pos_control_run - runs the guided position controller // called from guided_run static void guided_pos_control_run() { // process pilot's yaw input float target_yaw_rate = 0; if (!failsafe.radio) { // get pilot's desired yaw rate target_yaw_rate = get_pilot_desired_yaw_rate(g.rc_4.control_in); if (target_yaw_rate != 0) { set_auto_yaw_mode(AUTO_YAW_HOLD); } } // run waypoint controller wp_nav.update_wpnav(); // call z-axis position controller (wpnav should have already updated it's alt target) pos_control.update_z_controller(); // call attitude controller if (auto_yaw_mode == AUTO_YAW_HOLD) { // roll & pitch from waypoint controller, yaw rate from pilot attitude_control.angle_ef_roll_pitch_rate_ef_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate); }else{ // roll, pitch from waypoint controller, yaw heading from auto_heading() attitude_control.angle_ef_roll_pitch_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), get_auto_heading(), true); } } // guided_vel_control_run - runs the guided velocity controller // called from guided_run static void guided_vel_control_run() { // process pilot's yaw input float target_yaw_rate = 0; if (!failsafe.radio) { // get pilot's desired yaw rate target_yaw_rate = get_pilot_desired_yaw_rate(g.rc_4.control_in); if (target_yaw_rate != 0) { set_auto_yaw_mode(AUTO_YAW_HOLD); } } // call velocity controller which includes z axis controller pos_control.update_vel_controller_xyz(ekfNavVelGainScaler); // call attitude controller if (auto_yaw_mode == AUTO_YAW_HOLD) { // roll & pitch from waypoint controller, yaw rate from pilot attitude_control.angle_ef_roll_pitch_rate_ef_yaw(pos_control.get_roll(), pos_control.get_pitch(), target_yaw_rate); }else{ // roll, pitch from waypoint controller, yaw heading from auto_heading() attitude_control.angle_ef_roll_pitch_yaw(pos_control.get_roll(), pos_control.get_pitch(), get_auto_heading(), true); } } // guided_posvel_control_run - runs the guided spline controller // called from guided_run static void guided_posvel_control_run() { // process pilot's yaw input float target_yaw_rate = 0; if (!failsafe.radio) { // get pilot's desired yaw rate target_yaw_rate = get_pilot_desired_yaw_rate(g.rc_4.control_in); if (target_yaw_rate != 0) { set_auto_yaw_mode(AUTO_YAW_HOLD); } } // set velocity to zero if no updates received for 3 seconds uint32_t tnow = millis(); if (tnow - posvel_update_time_ms > GUIDED_POSVEL_TIMEOUT_MS && !posvel_vel_target_cms.is_zero()) { posvel_vel_target_cms.zero(); } // advance position target using velocity target posvel_pos_target_cm += posvel_vel_target_cms * G_Dt; // send position and velocity targets to position controller pos_control.set_pos_target(posvel_pos_target_cm); pos_control.set_desired_velocity_xy(posvel_vel_target_cms.x, posvel_vel_target_cms.y); // run position controller pos_control.update_xy_controller(AC_PosControl::XY_MODE_POS_AND_VEL_FF, ekfNavVelGainScaler); pos_control.update_z_controller(); // call attitude controller if (auto_yaw_mode == AUTO_YAW_HOLD) { // roll & pitch from waypoint controller, yaw rate from pilot attitude_control.angle_ef_roll_pitch_rate_ef_yaw(pos_control.get_roll(), pos_control.get_pitch(), target_yaw_rate); }else{ // roll, pitch from waypoint controller, yaw heading from auto_heading() attitude_control.angle_ef_roll_pitch_yaw(pos_control.get_roll(), pos_control.get_pitch(), get_auto_heading(), true); } } // Guided Limit code // guided_limit_clear - clear/turn off guided limits static void guided_limit_clear() { guided_limit.timeout_ms = 0; guided_limit.alt_min_cm = 0.0f; guided_limit.alt_max_cm = 0.0f; guided_limit.horiz_max_cm = 0.0f; } // guided_limit_set - set guided timeout and movement limits static void guided_limit_set(uint32_t timeout_ms, float alt_min_cm, float alt_max_cm, float horiz_max_cm) { guided_limit.timeout_ms = timeout_ms; guided_limit.alt_min_cm = alt_min_cm; guided_limit.alt_max_cm = alt_max_cm; guided_limit.horiz_max_cm = horiz_max_cm; } // guided_limit_init_time_and_pos - initialise guided start time and position as reference for limit checking // only called from AUTO mode's auto_nav_guided_start function static void guided_limit_init_time_and_pos() { // initialise start time guided_limit.start_time = hal.scheduler->millis(); // initialise start position from current position guided_limit.start_pos = inertial_nav.get_position(); } // guided_limit_check - returns true if guided mode has breached a limit // used when guided is invoked from the NAV_GUIDED_ENABLE mission command static bool guided_limit_check() { // check if we have passed the timeout if ((guided_limit.timeout_ms > 0) && (millis() - guided_limit.start_time >= guided_limit.timeout_ms)) { return true; } // get current location const Vector3f& curr_pos = inertial_nav.get_position(); // check if we have gone below min alt if ((guided_limit.alt_min_cm != 0.0f) && (curr_pos.z < guided_limit.alt_min_cm)) { return true; } // check if we have gone above max alt if ((guided_limit.alt_max_cm != 0.0f) && (curr_pos.z > guided_limit.alt_max_cm)) { return true; } // check if we have gone beyond horizontal limit if (guided_limit.horiz_max_cm > 0.0f) { float horiz_move = pv_get_horizontal_distance_cm(guided_limit.start_pos, curr_pos); if (horiz_move > guided_limit.horiz_max_cm) { return true; } } // if we got this far we must be within limits return false; }