Skip to content

Commit

Permalink
costmap layers
Browse files Browse the repository at this point in the history
  • Loading branch information
meshvaD committed Nov 8, 2023
1 parent 417208b commit 76a32c5
Show file tree
Hide file tree
Showing 6 changed files with 175 additions and 64 deletions.
Original file line number Diff line number Diff line change
@@ -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:
Expand All @@ -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
Expand All @@ -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
Expand Down Expand Up @@ -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
Expand All @@ -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
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand All @@ -57,7 +57,7 @@ lidar:
offset:
x: 0.61
y: 0
z: 0.1
z: 0.15

r_rot: 0
p_rot: 0
Expand Down
Original file line number Diff line number Diff line change
@@ -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


Expand Down Expand Up @@ -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']),
Expand All @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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',
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,8 +50,8 @@
<xacro:generate_sensor_frame sensor_params="${sensors_parameters['depth_camera']['camera1']}" name="camera1"/>
<xacro:default_depth_camera_frame camera_link_name="camera1" camera_props="${sensors_parameters['depth_camera']['camera1']['camera_properties']}"/>

<xacro:generate_sensor_frame sensor_params="${sensors_parameters['depth_camera']['camera2']}" name="camera2"/>
<xacro:default_depth_camera_frame camera_link_name="camera2" camera_props="${sensors_parameters['depth_camera']['camera2']['camera_properties']}"/>
<!-- <xacro:generate_sensor_frame sensor_params="${sensors_parameters['depth_camera']['camera2']}" name="camera2"/>
<xacro:default_depth_camera_frame camera_link_name="camera2" camera_props="${sensors_parameters['depth_camera']['camera2']['camera_properties']}"/> -->

<xacro:generate_sensor_frame sensor_params="${sensors_parameters['lidar']['lidar1']}" name="lidar1"/>
<xacro:default_lidar_frame lidar_link_name="lidar1" lidar_props="${sensors_parameters['lidar']['lidar1']['lidar_properties']}"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,19 @@


<xacro:macro name="default_depth_camera_frame" params="camera_link_name camera_props">

<!-- need virtual joint due to axis misalignment -->
<link name="${camera_link_name}_virtual_link">
<visual>
</visual>
</link>

<joint type="fixed" name="${camera_link_name}_virtual_joint">
<origin rpy="${-pi/2} 0 ${-pi/2}" xyz="0 0 0"/>
<child link="${camera_link_name}_virtual_link"/>
<parent link="${camera_link_name}"/>
</joint>

<gazebo reference="${camera_link_name}">
<sensor name="${camera_link_name}_sensor" type="depth">
<visualize>true</visualize>
Expand All @@ -48,17 +61,10 @@
</camera>
<plugin name="depth_camera_controller" filename="libgazebo_ros_camera.so">
<cameraName>${camera_link_name}</cameraName>
<imageTopicName>${camera_link_name}_ir/image_raw</imageTopicName>
<cameraInfoTopicName>${camera_link_name}_ir/camera_info</cameraInfoTopicName>
<depthImageTopicName>${camera_link_name}_depth/image_raw</depthImageTopicName>
<depthImageCameraInfoTopicName>${camera_link_name}_depth/camera_info</depthImageCameraInfoTopicName>
<pointCloudTopicName>${camera_link_name}_depth/points</pointCloudTopicName>
<frameName>${camera_link_name}_optical_frame</frameName>

<frame_name>${camera_link_name}_virtual_link</frame_name>
<baseline>0.2</baseline>
<alwaysOn>true</alwaysOn>
<updateRate>0.0</updateRate>
<frame_name>camera_depth_frame</frame_name>
<pointCloudCutoff>0.5</pointCloudCutoff>
<pointCloudCutoffMax>3.0</pointCloudCutoffMax>
<distortionK1>0</distortionK1>
Expand Down

0 comments on commit 76a32c5

Please sign in to comment.