diff --git a/uwrt_mars_rover_drivetrain/uwrt_mars_rover_drivetrain_description/config/costmap_parameters.yaml b/uwrt_mars_rover_drivetrain/uwrt_mars_rover_drivetrain_description/config/costmap_parameters.yaml
index cb57c242..53fb9415 100644
--- a/uwrt_mars_rover_drivetrain/uwrt_mars_rover_drivetrain_description/config/costmap_parameters.yaml
+++ b/uwrt_mars_rover_drivetrain/uwrt_mars_rover_drivetrain_description/config/costmap_parameters.yaml
@@ -1,10 +1,73 @@
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:
@@ -25,18 +88,18 @@ global_costmap:
global_frame: map
robot_base_frame: base_link
use_sim_time: True
- robot_radius: 0.22 # radius set and used, so no footprint points
+ robot_radius: 0.22 # should modify
resolution: 0.05
- plugins: ["static_layer", "voxel_layer", "inflation_layer", "obstacle_layer"]
+ plugins: ["static_layer", "inflation_layer", "obstacle_layer"]
obstacle_layer:
plugin: "nav2_costmap_2d::ObstacleLayer"
enabled: True
- observation_sources: scan
+ observation_sources: scan pointcloud1 pointcloud2
footprint_clearing_enabled: true
max_obstacle_height: 2.0
combination_method: 1
scan:
- topic: /scan
+ topic: /lidar_controller/out
obstacle_max_range: 2.5
obstacle_min_range: 0.0
raytrace_max_range: 3.0
@@ -47,20 +110,6 @@ global_costmap:
marking: True
data_type: "LaserScan"
inf_is_valid: false
- voxel_layer:
- plugin: "nav2_costmap_2d::VoxelLayer"
- enabled: True
- footprint_clearing_enabled: true
- max_obstacle_height: 2.0
- publish_voxel_map: True
- origin_z: 0.0
- z_resolution: 0.05
- z_voxels: 16
- max_obstacle_height: 2.0
- unknown_threshold: 15
- mark_threshold: 0
- observation_sources: pointcloud1, pointcloud2
- combination_method: 1
pointcloud1:
topic: /camera1_sensor/points
clearing: True
@@ -91,7 +140,7 @@ local_costmap:
local_costmap:
ros__parameters:
update_frequency: 5.0
- publish_frequency: 2.0
+ publish_frequency: 100.0
global_frame: base_link
robot_base_frame: base_link
use_sim_time: True
@@ -100,8 +149,69 @@ local_costmap:
height: 3
resolution: 0.05
+ plugins: ["static_layer", "inflation_layer", "obstacle_layer"]
+ obstacle_layer:
+ plugin: "nav2_costmap_2d::ObstacleLayer"
+ enabled: True
+ observation_sources: scan pointcloud1 pointcloud2
+ footprint_clearing_enabled: true
+ max_obstacle_height: 2.0
+ combination_method: 1
+ scan:
+ topic: /lidar_controller/out
+ data_type: "LaserScan"
+ sensor_frame: lidar1
+ marking: true
+ clearing: true
+ observation_persistence: 100.0
+ pointcloud1:
+ topic: /camera1_sensor/points
+ clearing: True
+ marking: True
+ data_type: "PointCloud2"
+ sensor_frame: camera1_virtual_link
+ marking: true
+ clearing: true
+ observation_persistence: 100.0
+ pointcloud2:
+ topic: /camera2_sensor/points
+ clearing: True
+ marking: True
+ data_type: "PointCloud2"
+ sensor_frame: camera2_virtual_link
+ marking: true
+ clearing: true
+ observation_persistence: 100.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: "map.yaml"
topic_name: "map"
frame_id: "map"
+
+costmap_filter_info_server:
+ ros__parameters:
+ type: 1
+ filter_info_topic: "costmap_filter_info"
+ mask_topic: "filter_mask"
+ base: 0.0
+ multiplier: 0.25
diff --git a/uwrt_mars_rover_drivetrain/uwrt_mars_rover_drivetrain_description/config/sensor_parameters.yaml b/uwrt_mars_rover_drivetrain/uwrt_mars_rover_drivetrain_description/config/sensor_parameters.yaml
index 2f6e79cb..e7d73acc 100644
--- a/uwrt_mars_rover_drivetrain/uwrt_mars_rover_drivetrain_description/config/sensor_parameters.yaml
+++ b/uwrt_mars_rover_drivetrain/uwrt_mars_rover_drivetrain_description/config/sensor_parameters.yaml
@@ -23,29 +23,29 @@ depth_camera:
near: 0.05
far: 3
- camera2:
- dim:
- length: 0.05
- width: 0.05
- height: 0.05
- parent_link: chassis
- offset:
- x: -0.61
- y: 0
- z: 0
+ # camera2:
+ # dim:
+ # length: 0.05
+ # width: 0.05
+ # height: 0.05
+ # parent_link: chassis
+ # offset:
+ # x: -0.61
+ # y: 0
+ # z: 0
- r_rot: 0
- p_rot: 0
- y_rot: 3.14159265359
- camera_properties:
- horizontal_fov: 1.047198
- image:
- width: 640
- height: 480
- format: R8G8B8
- clip:
- near: 0.05
- far: 3
+ # r_rot: 0
+ # p_rot: 0
+ # y_rot: 3.14159265359
+ # camera_properties:
+ # horizontal_fov: 1.047198
+ # image:
+ # width: 640
+ # height: 480
+ # format: R8G8B8
+ # clip:
+ # near: 0.05
+ # far: 3
lidar:
lidar1:
@@ -57,7 +57,7 @@ lidar:
offset:
x: 0.61
y: 0
- z: 0.1
+ z: 0.15
r_rot: 0
p_rot: 0
diff --git a/uwrt_mars_rover_drivetrain/uwrt_mars_rover_drivetrain_description/launch/gazebo.launch.py b/uwrt_mars_rover_drivetrain/uwrt_mars_rover_drivetrain_description/launch/gazebo.launch.py
index a8e71f59..57c97d84 100644
--- a/uwrt_mars_rover_drivetrain/uwrt_mars_rover_drivetrain_description/launch/gazebo.launch.py
+++ b/uwrt_mars_rover_drivetrain/uwrt_mars_rover_drivetrain_description/launch/gazebo.launch.py
@@ -1,7 +1,7 @@
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
-from launch.actions import IncludeLaunchDescription
+from launch.actions import IncludeLaunchDescription, DeclareLaunchArgument
from launch.launch_description_sources import PythonLaunchDescriptionSource
@@ -33,8 +33,6 @@ def generate_launch_description():
'use_sim_time': True}] # add other parameters here if required
)
-
-
gazebo = IncludeLaunchDescription(
PythonLaunchDescriptionSource([os.path.join(
get_package_share_directory('gazebo_ros'), 'launch'), '/gazebo.launch.py']),
@@ -46,13 +44,15 @@ def generate_launch_description():
'-entity', 'my_bot'],
output='screen')
-
-
-
+ world_argument = DeclareLaunchArgument(
+ name='world',
+ default_value=world_path,
+ description='Full path to the world model file to load')
# Run the node
return LaunchDescription([
+ # world_argument,
gazebo,
node_robot_state_publisher,
spawn_entity
diff --git a/uwrt_mars_rover_drivetrain/uwrt_mars_rover_drivetrain_description/launch/nav.launch.py b/uwrt_mars_rover_drivetrain/uwrt_mars_rover_drivetrain_description/launch/nav.launch.py
index 5fde1557..fbb95edb 100644
--- a/uwrt_mars_rover_drivetrain/uwrt_mars_rover_drivetrain_description/launch/nav.launch.py
+++ b/uwrt_mars_rover_drivetrain/uwrt_mars_rover_drivetrain_description/launch/nav.launch.py
@@ -19,16 +19,11 @@ def generate_launch_description():
'planner_server',
'map_server']
- map_server_config_path = os.path.join(
- get_package_share_directory('uwrt_mars_rover_drivetrain_description'),
- 'config',
- 'map.yaml'
- )
nodes += [Node(
package='nav2_map_server',
executable='map_server',
output='screen',
- parameters=[{'yaml_filename': map_server_config_path}])]
+ parameters=[controller_yaml])]
nodes += [Node(
package='nav2_controller',
diff --git a/uwrt_mars_rover_drivetrain/uwrt_mars_rover_drivetrain_description/urdf/drivetrain.urdf.xacro b/uwrt_mars_rover_drivetrain/uwrt_mars_rover_drivetrain_description/urdf/drivetrain.urdf.xacro
index 897b1cdd..1651a87c 100644
--- a/uwrt_mars_rover_drivetrain/uwrt_mars_rover_drivetrain_description/urdf/drivetrain.urdf.xacro
+++ b/uwrt_mars_rover_drivetrain/uwrt_mars_rover_drivetrain_description/urdf/drivetrain.urdf.xacro
@@ -50,8 +50,8 @@
-
-
+
diff --git a/uwrt_mars_rover_drivetrain/uwrt_mars_rover_drivetrain_description/urdf/sensors.macro.xacro b/uwrt_mars_rover_drivetrain/uwrt_mars_rover_drivetrain_description/urdf/sensors.macro.xacro
index 31da8895..73c4fd67 100644
--- a/uwrt_mars_rover_drivetrain/uwrt_mars_rover_drivetrain_description/urdf/sensors.macro.xacro
+++ b/uwrt_mars_rover_drivetrain/uwrt_mars_rover_drivetrain_description/urdf/sensors.macro.xacro
@@ -30,6 +30,19 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
true
@@ -48,17 +61,10 @@
${camera_link_name}
- ${camera_link_name}_ir/image_raw
- ${camera_link_name}_ir/camera_info
- ${camera_link_name}_depth/image_raw
- ${camera_link_name}_depth/camera_info
- ${camera_link_name}_depth/points
- ${camera_link_name}_optical_frame
-
+ ${camera_link_name}_virtual_link
0.2
true
0.0
- camera_depth_frame
0.5
3.0
0