-
Notifications
You must be signed in to change notification settings - Fork 7
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
* simple costmap using 2 cameras, 1 lidar * costmap layers * change sensors used * allow clearing obstacles
- Loading branch information
Showing
8 changed files
with
320 additions
and
61 deletions.
There are no files selected for viewing
189 changes: 189 additions & 0 deletions
189
...rs_rover_drivetrain/uwrt_mars_rover_drivetrain_description/config/costmap_parameters.yaml
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,189 @@ | ||
controller_server: | ||
ros__parameters: | ||
use_sim_time: True | ||
controller_frequency: 20.0 | ||
min_x_velocity_threshold: 0.001 | ||
min_y_velocity_threshold: 0.5 | ||
min_theta_velocity_threshold: 0.001 | ||
failure_tolerance: 0.3 | ||
progress_checker_plugin: "progress_checker" | ||
goal_checker_plugins: ["general_goal_checker"] # "precise_goal_checker" | ||
controller_plugins: ["FollowPath"] | ||
|
||
# Progress checker parameters | ||
progress_checker: | ||
plugin: "nav2_controller::SimpleProgressChecker" | ||
required_movement_radius: 0.5 | ||
movement_time_allowance: 10.0 | ||
# Goal checker parameters | ||
#precise_goal_checker: | ||
# plugin: "nav2_controller::SimpleGoalChecker" | ||
# xy_goal_tolerance: 0.25 | ||
# yaw_goal_tolerance: 0.25 | ||
# stateful: True | ||
general_goal_checker: | ||
stateful: True | ||
plugin: "nav2_controller::SimpleGoalChecker" | ||
xy_goal_tolerance: 0.25 | ||
yaw_goal_tolerance: 0.25 | ||
# DWB parameters | ||
FollowPath: | ||
plugin: "dwb_core::DWBLocalPlanner" | ||
debug_trajectory_details: True | ||
min_vel_x: 0.0 | ||
min_vel_y: 0.0 | ||
max_vel_x: 0.26 | ||
max_vel_y: 0.0 | ||
max_vel_theta: 1.0 | ||
min_speed_xy: 0.0 | ||
max_speed_xy: 0.26 | ||
min_speed_theta: 0.0 | ||
# Add high threshold velocity for turtlebot 3 issue. | ||
# https://github.com/ROBOTIS-GIT/turtlebot3_simulations/issues/75 | ||
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.25 | ||
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 | ||
PathAlign.forward_point_distance: 0.1 | ||
GoalAlign.scale: 24.0 | ||
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: -1.0 | ||
|
||
planner_server: | ||
ros__parameters: | ||
expected_planner_frequency: 20.0 | ||
planner_plugins: ["GridBased"] | ||
GridBased: | ||
plugin: "nav2_navfn_planner/NavfnPlanner" | ||
tolerance: 0.5 | ||
use_astar: false | ||
allow_unknown: true | ||
|
||
global_costmap: | ||
global_costmap: | ||
ros__parameters: | ||
footprint_padding: 0.03 | ||
update_frequency: 5.0 | ||
publish_frequency: 5.0 | ||
global_frame: odom | ||
robot_base_frame: base_link | ||
use_sim_time: True | ||
robot_radius: 0.22 # should modify | ||
resolution: 0.05 | ||
plugins: ["static_layer", "obstacle_layer", "inflation_layer"] | ||
obstacle_layer: | ||
plugin: "nav2_costmap_2d::ObstacleLayer" | ||
enabled: True | ||
observation_sources: pointcloud1 | ||
footprint_clearing_enabled: true | ||
combination_method: 0 | ||
pointcloud1: | ||
topic: /camera1_sensor/points | ||
sensor_frame: camera1 | ||
clearing: True | ||
marking: True | ||
data_type: "PointCloud2" | ||
min_obstacle_height: 0.001 | ||
max_obstacle_height: 10.0 | ||
denoise_layer: | ||
plugin: "nav2_costmap_2d::DenoiseLayer" | ||
enabled: True | ||
minimal_group_size: 2 | ||
group_connectivity_type: 8 | ||
static_layer: | ||
plugin: "nav2_costmap_2d::StaticLayer" | ||
map_subscribe_transient_local: True | ||
enabled: true | ||
subscribe_to_updates: true | ||
transform_tolerance: 0.1 | ||
inflation_layer: | ||
plugin: "nav2_costmap_2d::InflationLayer" | ||
enabled: true | ||
inflation_radius: 0.55 | ||
cost_scaling_factor: 1.0 | ||
inflate_unknown: false | ||
inflate_around_unknown: true | ||
always_send_full_costmap: True | ||
|
||
|
||
local_costmap: | ||
local_costmap: | ||
ros__parameters: | ||
update_frequency: 5.0 | ||
publish_frequency: 5.0 | ||
global_frame: odom | ||
robot_base_frame: base_link | ||
use_sim_time: True | ||
rolling_window: true | ||
width: 3 | ||
height: 3 | ||
resolution: 0.05 | ||
|
||
plugins: ["static_layer", "obstacle_layer", "inflation_layer"] | ||
obstacle_layer: | ||
plugin: "nav2_costmap_2d::ObstacleLayer" | ||
enabled: True | ||
observation_sources: pointcloud1 | ||
footprint_clearing_enabled: true | ||
combination_method: 0 | ||
pointcloud1: | ||
topic: /camera1_sensor/points | ||
sensor_frame: camera1 | ||
clearing: True | ||
marking: True | ||
data_type: "PointCloud2" | ||
min_obstacle_height: 0.001 | ||
max_obstacle_height: 10.0 | ||
static_layer: | ||
plugin: "nav2_costmap_2d::StaticLayer" | ||
map_subscribe_transient_local: True | ||
enabled: true | ||
subscribe_to_updates: true | ||
transform_tolerance: 0.1 | ||
inflation_layer: | ||
plugin: "nav2_costmap_2d::InflationLayer" | ||
enabled: true | ||
inflation_radius: 0.55 | ||
cost_scaling_factor: 1.0 | ||
inflate_unknown: false | ||
inflate_around_unknown: true | ||
|
||
map_saver: | ||
ros__parameters: | ||
save_map_timeout: 5.0 | ||
free_thresh_default: 0.25 | ||
occupied_thresh_default: 0.65 | ||
|
||
map_server: | ||
ros__parameters: | ||
yaml_filename: "/home/meshva/uwrt/uwrt_mars_rover/uwrt_mars_rover_drivetrain/uwrt_mars_rover_drivetrain_description/config/map.yaml" | ||
topic_name: "map" | ||
frame_id: "odom" | ||
|
||
costmap_filter_info_server: | ||
ros__parameters: | ||
type: 1 | ||
filter_info_topic: "costmap_filter_info" | ||
mask_topic: "filter_mask" | ||
base: 0.0 | ||
multiplier: 0.25 |
5 changes: 5 additions & 0 deletions
5
uwrt_mars_rover_drivetrain/uwrt_mars_rover_drivetrain_description/config/map.pgm
Large diffs are not rendered by default.
Oops, something went wrong.
6 changes: 6 additions & 0 deletions
6
uwrt_mars_rover_drivetrain/uwrt_mars_rover_drivetrain_description/config/map.yaml
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,6 @@ | ||
image: map.pgm | ||
resolution: 0.050000 | ||
origin: [-10.000000, -10.000000, 0.000000] | ||
negate: 0 | ||
occupied_thresh: 0.65 | ||
free_thresh: 0.196 |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
53 changes: 53 additions & 0 deletions
53
uwrt_mars_rover_drivetrain/uwrt_mars_rover_drivetrain_description/launch/nav.launch.py
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,53 @@ | ||
from ament_index_python.packages import get_package_share_directory | ||
|
||
from launch import LaunchDescription | ||
from launch_ros.actions import Node | ||
from launch.actions import DeclareLaunchArgument | ||
from launch.substitutions import LaunchConfiguration | ||
from launch_ros.descriptions import ParameterFile | ||
|
||
import os | ||
|
||
def generate_launch_description(): | ||
|
||
declared_arguments = [] | ||
nodes = [] | ||
|
||
controller_yaml = os.path.join(get_package_share_directory('uwrt_mars_rover_drivetrain_description'), 'config', 'costmap_parameters.yaml') | ||
|
||
lifecycle_nodes = ['controller_server', | ||
'planner_server', | ||
'map_server'] | ||
|
||
nodes += [Node( | ||
package='nav2_map_server', | ||
executable='map_server', | ||
output='screen', | ||
parameters=[controller_yaml])] | ||
|
||
nodes += [Node( | ||
package='nav2_controller', | ||
executable='controller_server', | ||
output='screen', | ||
respawn=True, | ||
respawn_delay=2.0, | ||
parameters=[controller_yaml])] | ||
|
||
nodes += [Node( | ||
package='nav2_planner', | ||
executable='planner_server', | ||
name='planner_server', | ||
output='screen', | ||
respawn=True, | ||
respawn_delay=2.0, | ||
parameters=[controller_yaml])] | ||
|
||
nodes += [Node( | ||
package='nav2_lifecycle_manager', | ||
executable='lifecycle_manager', | ||
name='lifecycle_manager_navigation', | ||
output='screen', | ||
parameters=[{'autostart': True}, | ||
{'node_names': lifecycle_nodes}])] | ||
|
||
return LaunchDescription(declared_arguments + nodes) |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Oops, something went wrong.