void Rover::calc_lateral_acceleration() { switch (control_mode) { case AUTO: // If we have reached the waypoint previously navigate // back to it from our current position if (previously_reached_wp && (loiter_duration > 0)) { nav_controller->update_waypoint(current_loc, next_WP); } else { nav_controller->update_waypoint(prev_WP, next_WP); } break; case RTL: case GUIDED: case STEERING: nav_controller->update_waypoint(current_loc, next_WP); break; default: return; } // Calculate the required turn of the wheels // negative error = left turn // positive error = right turn lateral_acceleration = nav_controller->lateral_acceleration(); if (use_pivot_steering()) { const int16_t bearing_error = wrap_180_cd(nav_controller->target_bearing_cd() - ahrs.yaw_sensor) / 100; if (bearing_error > 0) { lateral_acceleration = g.turn_max_g * GRAVITY_MSS; } else { lateral_acceleration = -g.turn_max_g * GRAVITY_MSS; } } }
// calculate steering output to drive along line from origin to destination waypoint // relies on update_distance_and_bearing_to_destination being called first so _wp_bearing_cd has been updated void AR_WPNav::update_steering(const Location& current_loc, float current_speed) { // calculate yaw error for determining if vehicle should pivot towards waypoint float yaw_cd = _reversed ? wrap_360_cd(_wp_bearing_cd + 18000) : _wp_bearing_cd; float yaw_error_cd = wrap_180_cd(yaw_cd - AP::ahrs().yaw_sensor); // calculate desired turn rate and update desired heading if (use_pivot_steering(yaw_error_cd)) { _cross_track_error = 0.0f; _desired_heading_cd = yaw_cd; _desired_lat_accel = 0.0f; _desired_turn_rate_rads = _atc.get_turn_rate_from_heading(radians(yaw_cd * 0.01f), radians(_pivot_rate)); } else { // run L1 controller _nav_controller.set_reverse(_reversed); _nav_controller.update_waypoint((_reached_destination ? current_loc : _origin), _destination, _radius); // retrieve lateral acceleration, heading back towards line and crosstrack error _desired_lat_accel = constrain_float(_nav_controller.lateral_acceleration(), -_turn_max_mss, _turn_max_mss); _desired_heading_cd = wrap_360_cd(_nav_controller.nav_bearing_cd()); if (_reversed) { _desired_lat_accel *= -1.0f; _desired_heading_cd = wrap_360_cd(_desired_heading_cd + 18000); } _cross_track_error = _nav_controller.crosstrack_error(); _desired_turn_rate_rads = _atc.get_turn_rate_from_lat_accel(_desired_lat_accel, current_speed); } }
/* calculate the throtte for auto-throttle modes */ void Rover::calc_throttle(float target_speed) { // If not autostarting OR we are loitering at a waypoint // then set the throttle to minimum if (!auto_check_trigger() || in_stationary_loiter()) { SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, g.throttle_min.get()); // Stop rotation in case of loitering and skid steering if (g.skid_steer_out) { SRV_Channels::set_output_scaled(SRV_Channel::k_steering, 0); } return; } const float throttle_base = (fabsf(target_speed) / g.speed_cruise) * g.throttle_cruise; const int throttle_target = throttle_base + throttle_nudge; /* reduce target speed in proportion to turning rate, up to the SPEED_TURN_GAIN percentage. */ float steer_rate = fabsf(lateral_acceleration / (g.turn_max_g*GRAVITY_MSS)); steer_rate = constrain_float(steer_rate, 0.0f, 1.0f); // use g.speed_turn_gain for a 90 degree turn, and in proportion // for other turn angles const int32_t turn_angle = wrap_180_cd(next_navigation_leg_cd - ahrs.yaw_sensor); const float speed_turn_ratio = constrain_float(fabsf(turn_angle / 9000.0f), 0, 1); const float speed_turn_reduction = (100 - g.speed_turn_gain) * speed_turn_ratio * 0.01f; float reduction = 1.0f - steer_rate * speed_turn_reduction; if (control_mode >= AUTO && wp_distance <= g.speed_turn_dist) { // in auto-modes we reduce speed when approaching waypoints const float reduction2 = 1.0f - speed_turn_reduction; if (reduction2 < reduction) { reduction = reduction2; } } // reduce the target speed by the reduction factor target_speed *= reduction; groundspeed_error = fabsf(target_speed) - ground_speed; throttle = throttle_target + (g.pidSpeedThrottle.get_pid(groundspeed_error * 100) / 100); // also reduce the throttle by the reduction factor. This gives a // much faster response in turns throttle *= reduction; if (in_reverse) { SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, constrain_int16(-throttle, -g.throttle_max, -g.throttle_min)); } else { SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, constrain_int16(throttle, g.throttle_min, g.throttle_max)); } if (!in_reverse && g.braking_percent != 0 && groundspeed_error < -g.braking_speederr) { // the user has asked to use reverse throttle to brake. Apply // it in proportion to the ground speed error, but only when // our ground speed error is more than BRAKING_SPEEDERR. // // We use a linear gain, with 0 gain at a ground speed error // of braking_speederr, and 100% gain when groundspeed_error // is 2*braking_speederr const float brake_gain = constrain_float(((-groundspeed_error)-g.braking_speederr)/g.braking_speederr, 0, 1); const int16_t braking_throttle = g.throttle_max * (g.braking_percent * 0.01f) * brake_gain; SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, constrain_int16(-braking_throttle, -g.throttle_max, -g.throttle_min)); // temporarily set us in reverse to allow the PWM setting to // go negative set_reverse(true); } if (use_pivot_steering()) { SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0); } }