mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
Rover: rename calc_nav_steer to calc_steering_from_lateral_acceleration
rename calc_lateral_acceleration to calc_steering_to_waypoint calc_steering_to_waypoint internally calls calc_steering_from_lateral_acceleration non-functional change
This commit is contained in:
parent
3d6cc59a6b
commit
c6689fd2e1
@ -190,7 +190,7 @@ float Mode::calc_reduced_speed_for_turn_or_distance(float desired_speed)
|
|||||||
|
|
||||||
// calculate the lateral acceleration target to cause the vehicle to drive along the path from origin to destination
|
// calculate the lateral acceleration target to cause the vehicle to drive along the path from origin to destination
|
||||||
// this function update lateral_acceleration and _yaw_error_cd members
|
// this function update lateral_acceleration and _yaw_error_cd members
|
||||||
void Mode::calc_lateral_acceleration(const struct Location &origin, const struct Location &destination, bool reversed)
|
void Mode::calc_steering_to_waypoint(const struct Location &origin, const struct Location &destination, bool reversed)
|
||||||
{
|
{
|
||||||
// Calculate the required turn of the wheels
|
// Calculate the required turn of the wheels
|
||||||
// negative error = left turn
|
// negative error = left turn
|
||||||
@ -210,12 +210,15 @@ void Mode::calc_lateral_acceleration(const struct Location &origin, const struct
|
|||||||
lateral_acceleration = -g.turn_max_g * GRAVITY_MSS;
|
lateral_acceleration = -g.turn_max_g * GRAVITY_MSS;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// call lateral acceleration to steering controller
|
||||||
|
calc_steering_from_lateral_acceleration(reversed);
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
calculate steering angle given lateral_acceleration
|
calculate steering output given lateral_acceleration
|
||||||
*/
|
*/
|
||||||
void Mode::calc_nav_steer(bool reversed)
|
void Mode::calc_steering_from_lateral_acceleration(bool reversed)
|
||||||
{
|
{
|
||||||
// add obstacle avoidance response to lateral acceleration target
|
// add obstacle avoidance response to lateral acceleration target
|
||||||
if (!reversed) {
|
if (!reversed) {
|
||||||
|
@ -92,10 +92,10 @@ protected:
|
|||||||
virtual void _exit() { return; }
|
virtual void _exit() { return; }
|
||||||
|
|
||||||
// calculate steering angle given a desired lateral acceleration
|
// calculate steering angle given a desired lateral acceleration
|
||||||
void calc_nav_steer(bool reversed = false);
|
void calc_steering_from_lateral_acceleration(bool reversed = false);
|
||||||
|
|
||||||
// calculate desired lateral acceleration
|
// calculate steering output to drive along line from origin to destination waypoint
|
||||||
void calc_lateral_acceleration(const struct Location &origin, const struct Location &destination, bool reversed = false);
|
void calc_steering_to_waypoint(const struct Location &origin, const struct Location &destination, bool reversed = false);
|
||||||
|
|
||||||
// calculates the amount of throttle that should be output based
|
// calculates the amount of throttle that should be output based
|
||||||
// on things like proximity to corners and current speed
|
// on things like proximity to corners and current speed
|
||||||
@ -114,7 +114,7 @@ protected:
|
|||||||
float calc_speed_nudge(float target_speed, float cruise_speed, float cruise_throttle);
|
float calc_speed_nudge(float target_speed, float cruise_speed, float cruise_throttle);
|
||||||
|
|
||||||
// calculated a reduced speed(in m/s) based on yaw error and lateral acceleration and/or distance to a waypoint
|
// calculated a reduced speed(in m/s) based on yaw error and lateral acceleration and/or distance to a waypoint
|
||||||
// should be called after calc_lateral_acceleration and before calc_throttle
|
// should be called after calc_steering_to_waypoint and before calc_throttle
|
||||||
// relies on these internal members being updated: lateral_acceleration, _yaw_error_cd, _distance_to_destination
|
// relies on these internal members being updated: lateral_acceleration, _yaw_error_cd, _distance_to_destination
|
||||||
float calc_reduced_speed_for_turn_or_distance(float desired_speed);
|
float calc_reduced_speed_for_turn_or_distance(float desired_speed);
|
||||||
|
|
||||||
|
@ -54,8 +54,7 @@ void ModeAuto::update()
|
|||||||
bool active_at_destination = _reached_destination && _stay_active_at_dest && (_distance_to_destination > rover.g.waypoint_radius);
|
bool active_at_destination = _reached_destination && _stay_active_at_dest && (_distance_to_destination > rover.g.waypoint_radius);
|
||||||
if (!_reached_destination || active_at_destination) {
|
if (!_reached_destination || active_at_destination) {
|
||||||
// continue driving towards destination
|
// continue driving towards destination
|
||||||
calc_lateral_acceleration(active_at_destination ? rover.current_loc : _origin, _destination, _reversed);
|
calc_steering_to_waypoint(active_at_destination ? rover.current_loc : _origin, _destination, _reversed);
|
||||||
calc_nav_steer(_reversed);
|
|
||||||
calc_throttle(calc_reduced_speed_for_turn_or_distance(_reversed ? -_desired_speed : _desired_speed), true);
|
calc_throttle(calc_reduced_speed_for_turn_or_distance(_reversed ? -_desired_speed : _desired_speed), true);
|
||||||
} else {
|
} else {
|
||||||
// we have reached the destination so stop
|
// we have reached the destination so stop
|
||||||
|
@ -30,8 +30,7 @@ void ModeGuided::update()
|
|||||||
rover.gcs().send_mission_item_reached_message(0);
|
rover.gcs().send_mission_item_reached_message(0);
|
||||||
}
|
}
|
||||||
// drive towards destination
|
// drive towards destination
|
||||||
calc_lateral_acceleration(_origin, _destination);
|
calc_steering_to_waypoint(_origin, _destination);
|
||||||
calc_nav_steer();
|
|
||||||
calc_throttle(calc_reduced_speed_for_turn_or_distance(_desired_speed), true);
|
calc_throttle(calc_reduced_speed_for_turn_or_distance(_desired_speed), true);
|
||||||
} else {
|
} else {
|
||||||
stop_vehicle();
|
stop_vehicle();
|
||||||
|
@ -29,8 +29,7 @@ void ModeRTL::update()
|
|||||||
gcs().send_text(MAV_SEVERITY_INFO, "Reached destination");
|
gcs().send_text(MAV_SEVERITY_INFO, "Reached destination");
|
||||||
}
|
}
|
||||||
// continue driving towards destination
|
// continue driving towards destination
|
||||||
calc_lateral_acceleration(_origin, _destination);
|
calc_steering_to_waypoint(_origin, _destination);
|
||||||
calc_nav_steer();
|
|
||||||
calc_throttle(calc_reduced_speed_for_turn_or_distance(_desired_speed), true);
|
calc_throttle(calc_reduced_speed_for_turn_or_distance(_desired_speed), true);
|
||||||
} else {
|
} else {
|
||||||
// we've reached destination so stop
|
// we've reached destination so stop
|
||||||
|
@ -49,8 +49,8 @@ void ModeSteering::update()
|
|||||||
if (is_zero(target_speed) && !is_pivot_turning) {
|
if (is_zero(target_speed) && !is_pivot_turning) {
|
||||||
stop_vehicle();
|
stop_vehicle();
|
||||||
} else {
|
} else {
|
||||||
// run steering controller
|
// run lateral acceleration to steering controller
|
||||||
calc_nav_steer(reversed);
|
calc_steering_from_lateral_acceleration(false);
|
||||||
calc_throttle(target_speed, false);
|
calc_throttle(target_speed, false);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user