Skip to content

Commit

Permalink
dwb replaced by regulated pure pursuit
Browse files Browse the repository at this point in the history
  • Loading branch information
mgonzs13 committed Dec 7, 2023
1 parent ff38f12 commit 17ff996
Show file tree
Hide file tree
Showing 3 changed files with 33 additions and 50 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ def __init__(self):

self.declare_parameter("linear_limit", 1.0)
self.declare_parameter("angular_limit", 1.0)
self.declare_parameter("angular_factor", 0.5)
self.declare_parameter("angular_factor", 0.0)

# getting params
hardware_distances = self.get_parameter(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ VelParserNode::VelParserNode() : rclcpp::Node("vel_parser_node") {

this->declare_parameter<float>("linear_limit", 1.0);
this->declare_parameter<float>("angular_limit", 1.0);
this->declare_parameter<float>("angular_factor", 0.5);
this->declare_parameter<float>("angular_factor", 0.0);

// getting params
std::vector<double> hardware_distances;
Expand Down
79 changes: 31 additions & 48 deletions rover_navigation/params/nav2.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -88,55 +88,38 @@ controller_server:
yaw_goal_tolerance: 0.3
stateful: True

# DWB controller parameters
FollowPath:
plugin: dwb_core::DWBLocalPlanner
debug_trajectory_details: True
min_vel_x: 0.0
min_vel_y: 0.0
max_vel_x: 0.25
max_vel_y: 0.0
max_vel_theta: 1.0
min_speed_xy: 0.0
max_speed_xy: 0.25
min_speed_theta: 0.0
acc_lim_x: 2.5
acc_lim_y: 0.0
acc_lim_theta: 3.2
decel_lim_x: -2.5
decel_lim_y: 0.0
decel_lim_theta: -3.2
vx_samples: 20
vy_samples: 5
vtheta_samples: 20
sim_time: 1.7
linear_granularity: 0.05
angular_granularity: 0.025
transform_tolerance: 0.2
xy_goal_tolerance: 0.3
trans_stopped_velocity: 0.25
short_circuit_trajectory_evaluation: True
stateful: True
critics:
[
RotateToGoal,
Oscillation,
BaseObstacle,
GoalAlign,
PathAlign,
PathDist,
GoalDist,
]
BaseObstacle.scale: 0.02
PathAlign.scale: 32.0
GoalAlign.scale: 24.0
PathAlign.forward_point_distance: 0.1
GoalAlign.forward_point_distance: 0.1
PathDist.scale: 32.0
GoalDist.scale: 24.0
RotateToGoal.scale: 32.0
RotateToGoal.slowing_factor: 5.0
RotateToGoal.lookahead_time: 5.0
plugin: nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController
transform_tolerance: 1.0
desired_linear_vel: 0.25

lookahead_dist: 0.6
min_lookahead_dist: 0.3
max_lookahead_dist: 0.9
lookahead_time: 1.5

rotate_to_heading_angular_vel: 1.8

use_velocity_scaled_lookahead_dist: True
approach_velocity_scaling_dist: 1.0
min_approach_linear_velocity: 0.05
use_regulated_linear_velocity_scaling: True
use_cost_regulated_linear_velocity_scaling: True
regulated_linear_scaling_min_radius: 0.9
regulated_linear_scaling_min_speed: 0.25

use_collision_detection: False
max_allowed_time_to_collision_up_to_carrot: 1.0

use_rotate_to_heading: False
rotate_to_heading_min_angle: 0.785
max_angular_accel: 3.2
max_robot_pose_search_dist: 10.0
use_interpolation: True

cost_scaling_dist: 0.3
cost_scaling_gain: 1.0
inflation_cost_scaling_factor: 3.0

local_costmap:
local_costmap:
Expand Down

0 comments on commit 17ff996

Please sign in to comment.