Compare commits

...

1 Commits

Author SHA1 Message Date
9b9f26c145 update 2024-03-28 09:58:05 +01:00
4 changed files with 210 additions and 120 deletions

View File

@ -11,7 +11,7 @@ echo "Sourced ROS 2 ${ROS_DISTRO}"
if [ -f ${UNDERLAY_WS}/install/setup.bash ]
then
source ${UNDERLAY_WS}/install/setup.bash
vcs pull ${UNDERLAY_WS}/src
# vcs pull ${UNDERLAY_WS}/src
echo "Sourced CPS RMP 220 base workspace"
fi
@ -19,7 +19,7 @@ fi
if [ -f /overlay_ws/install/setup.bash ]
then
source /overlay_ws/install/setup.bash
vcs pull /overlay_ws/src
# vcs pull /overlay_ws/src
echo "Sourced CPS RMP 220 Overlay workspace"
fi
@ -32,67 +32,19 @@ then
fi
# Implement updating all repositories at launch
if [ -f ${UNDERLAY_WS}/]
then
cd ${UNDERLAY_WS}
vcs pull src
echo "Updated base workspace"
fi
if [ -f /overlay_ws/]
then
cd /overlay_ws
vcs pull src
echo "Updated overlay workspace"
fi
# configure container networking to use zerotier interface as standard gateway
# this might be for later
# if [ -f /zerotier-one/zerotier-cli ]
# if [ -f ${UNDERLAY_WS}/]
# then
# /zerotier-one/zerotier-cli join 8056c2e21c000001
# echo "Joined zerotier network"
# fi
# # set standard gateway to zerotier interface
# ip route del default
# ip route add default via $(ip addr show zt* | grep -Po 'inet \K[\d.]+')
# echo "Set zerotier interface as standard gateway"
# this should now route the ros2 traffic through zerotier?
# # Find the ZeroTier interface name dynamically
# zerotier_interface=$(ip addr show | awk '/^.*: zt/{print $2}' | cut -d ':' -f 1)
# if [ -z "$zerotier_interface" ]; then
# echo "ZeroTier interface not found."
# exit 1
# cd ${UNDERLAY_WS}
# vcs pull src
# echo "Updated base workspace"
# fi
# # Set the standard gateway to the ZeroTier interface
# ip route del default
# ip route add default via $(ip addr show "$zerotier_interface" | grep -Po 'inet \K[\d.]+')
# echo "Set ZeroTier interface '$zerotier_interface' as the standard gateway."
# Changing apporach to just configure the cyconedds to use the zerotier interface
# For now add respective ip apps to do the stuff below:
apt update && apt install -y iproute2
# Find the ZeroTier interface name dynamically
# zerotier_interface=$(ip addr show | awk '/^.*: zt/{print $2}' | cut -d ':' -f 1)
# if [ -z "$zerotier_interface" ]; then
# echo "ZeroTier interface not found."
# exit 1
# if [ -f /overlay_ws/]
# then
# cd /overlay_ws
# vcs pull src
# echo "Updated overlay workspace"
# fi
# echo "Using ZeroTier interface: $zerotier_interface"
# # Set the path to your CycloneDDS configuration file
# config_file="/cyclonedds.xml"
# # Replace the content between <NetworkInterfaceAddress> tags
# sed -i "s|<NetworkInterfaceAddress>.*</NetworkInterfaceAddress>|<NetworkInterfaceAddress>$zerotier_interface</NetworkInterfaceAddress>|g" "$config_file"
# Execute the command passed into this entrypoint
exec "$@"

View File

@ -254,52 +254,139 @@ bt_navigator_navigate_to_pose_rclcpp_node:
# RotateToGoal.scale: 32.0
# RotateToGoal.slowing_factor: 5.0
# RotateToGoal.lookahead_time: -1.0
# controller_server:
# ros__parameters:
# use_sim_time: True
# controller_frequency: 100.0 # was 20.0
# min_x_velocity_threshold: 0.001
# min_y_velocity_threshold: 0.5
# min_theta_velocity_threshold: 0.001
# progress_checker_plugins: ["progress_checker"] # progress_checker_plugin: "progress_checker" For Humble and older
# goal_checker_plugins: ["goal_checker"]
# controller_plugins: ["FollowPath"]
# progress_checker:
# plugin: "nav2_controller::SimpleProgressChecker"
# required_movement_radius: 0.5
# movement_time_allowance: 10.0
# goal_checker:
# plugin: "nav2_controller::SimpleGoalChecker"
# xy_goal_tolerance: 0.25 # was 0.25
# yaw_goal_tolerance: 0.25 # was 0.25
# stateful: True
# FollowPath:
# plugin: "nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController"
# desired_linear_vel: 0.5
# 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
# transform_tolerance: 0.1
# use_velocity_scaled_lookahead_dist: false
# min_approach_linear_velocity: 0.007 # was 0.05
# approach_velocity_scaling_dist: 0.6
# use_collision_detection: true
# max_allowed_time_to_collision_up_to_carrot: 1.0
# use_regulated_linear_velocity_scaling: true
# use_fixed_curvature_lookahead: false
# curvature_lookahead_dist: 0.25
# use_cost_regulated_linear_velocity_scaling: false
# regulated_linear_scaling_min_radius: 0.9
# regulated_linear_scaling_min_speed: 0.25
# use_rotate_to_heading: false # was true, cannot be set together with allow_reversing
# allow_reversing: true # was false
# rotate_to_heading_min_angle: 0.785
# max_angular_accel: 3.2
# max_robot_pose_search_dist: 10.0
# use_interpolation: true # was false
controller_server:
ros__parameters:
use_sim_time: True
controller_frequency: 100.0 # was 20.0
min_x_velocity_threshold: 0.001
min_y_velocity_threshold: 0.5
min_theta_velocity_threshold: 0.001
progress_checker_plugins: ["progress_checker"] # progress_checker_plugin: "progress_checker" For Humble and older
goal_checker_plugins: ["goal_checker"]
controller_plugins: ["FollowPath"]
progress_checker:
plugin: "nav2_controller::SimpleProgressChecker"
required_movement_radius: 0.5
movement_time_allowance: 10.0
goal_checker:
plugin: "nav2_controller::SimpleGoalChecker"
xy_goal_tolerance: 0.25 # was 0.25
yaw_goal_tolerance: 0.25 # was 0.25
stateful: True
controller_frequency: 50.0 # was 30.0 # ! must be float!
FollowPath:
plugin: "nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController"
desired_linear_vel: 0.5
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
plugin: "nav2_mppi_controller::MPPIController"
time_steps: 56
model_dt: 0.05
batch_size: 1000 # was 2000
vx_std: 0.2
vy_std: 0.2
wz_std: 0.4
vx_max: 0.5
vx_min: -0.35
vy_max: 0.5
wz_max: 1.9
iteration_count: 1
prune_distance: 1.7
transform_tolerance: 0.1
use_velocity_scaled_lookahead_dist: false
min_approach_linear_velocity: 0.007 # was 0.05
approach_velocity_scaling_dist: 0.6
use_collision_detection: true
max_allowed_time_to_collision_up_to_carrot: 1.0
use_regulated_linear_velocity_scaling: true
use_fixed_curvature_lookahead: false
curvature_lookahead_dist: 0.25
use_cost_regulated_linear_velocity_scaling: false
regulated_linear_scaling_min_radius: 0.9
regulated_linear_scaling_min_speed: 0.25
use_rotate_to_heading: false # was true, cannot be set together with allow_reversing
allow_reversing: true # was false
rotate_to_heading_min_angle: 0.785
max_angular_accel: 3.2
max_robot_pose_search_dist: 10.0
use_interpolation: true # was false
temperature: 0.3
gamma: 0.015
motion_model: "DiffDrive"
visualize: false
reset_period: 1.0 # (only in Humble)
regenerate_noises: false
TrajectoryVisualizer:
trajectory_step: 5
time_step: 3
AckermannConstraints:
min_turning_r: 0.1 # was0.2 # only active for ackermann
critics: ["ConstraintCritic", "ObstaclesCritic", "GoalCritic", "GoalAngleCritic", "PathAlignCritic", "PathFollowCritic", "PathAngleCritic", "PreferForwardCritic"]
ConstraintCritic:
enabled: true
cost_power: 1
cost_weight: 4.0
GoalCritic:
enabled: true
cost_power: 1
cost_weight: 5.0
threshold_to_consider: 1.4
GoalAngleCritic:
enabled: true
cost_power: 1
cost_weight: 3.0
threshold_to_consider: 0.5
PreferForwardCritic:
enabled: true
cost_power: 1
cost_weight: 10.0 # was 5.0
threshold_to_consider: 0.5
ObstaclesCritic:
enabled: true
cost_power: 1
repulsion_weight: 1.5
critical_weight: 20.0
consider_footprint: true # was false
collision_cost: 10000.0
collision_margin_distance: 0.1
near_goal_distance: 0.5
inflation_radius: 0.35 #was0.55 # (only in Humble)
cost_scaling_factor: 10.0 # (only in Humble)
PathAlignCritic:
enabled: true
cost_power: 1
cost_weight: 14.0
max_path_occupancy_ratio: 0.05
trajectory_point_step: 3
threshold_to_consider: 0.5
offset_from_furthest: 20
use_path_orientations: true # was false
PathFollowCritic:
enabled: true
cost_power: 1
cost_weight: 5.0
offset_from_furthest: 5
threshold_to_consider: 1.4
PathAngleCritic:
enabled: true
cost_power: 1
cost_weight: 2.0
offset_from_furthest: 4
threshold_to_consider: 0.5
max_angle_to_furthest: 1.0
mode: 0
# TwirlingCritic:
# enabled: true
# twirling_cost_power: 1
# twirling_cost_weight: 10.0
local_costmap:
@ -319,8 +406,8 @@ local_costmap:
plugins: ["voxel_layer", "inflation_layer"]
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
cost_scaling_factor: 2.0 # was 3.0 ;exponential rate at which the obstacle cost drops off (default: 10)
inflation_radius: 0.70 # max. distance from an obstacle at which costs are incurred for planning paths.
cost_scaling_factor: 10.0 # was 3.0 ;exponential rate at which the obstacle cost drops off (default: 10)
inflation_radius: 0.35 # max. distance from an obstacle at which costs are incurred for planning paths.
voxel_layer:
plugin: "nav2_costmap_2d::VoxelLayer"
enabled: True
@ -390,7 +477,7 @@ global_costmap:
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
cost_scaling_factor: 10.0 # was 3.0
inflation_radius: 0.55
inflation_radius: 0.35
always_send_full_costmap: True
map_server:
@ -418,27 +505,67 @@ map_saver:
# tolerance: 0.5
# use_astar: false
# allow_unknown: true
# planner_server:
# ros__parameters:
# planner_plugins: ["GridBased"]
# use_sim_time: True
# GridBased:
# plugin: "nav2_smac_planner/SmacPlanner2D"
# tolerance: 0.125 # tolerance for planning if unable to reach exact pose, in meters
# downsample_costmap: false # whether or not to downsample the map
# downsampling_factor: 1 # multiplier for the resolution of the costmap layer (e.g. 2 on a 5cm costmap would be 10cm)
# allow_unknown: true # allow traveling in unknown space
# max_iterations: 1000000 # maximum total iterations to search for before failing (in case unreachable), set to -1 to disable
# max_on_approach_iterations: 1000 # maximum number of iterations to attempt to reach goal once in tolerance
# max_planning_time: 2.0 # max time in s for planner to plan, smooth
# cost_travel_multiplier: 2.0 # Cost multiplier to apply to search to steer away from high cost areas. Larger values will place in the center of aisles more exactly (if non-`FREE` cost potential field exists) but take slightly longer to compute. To optimize for speed, a value of 1.0 is reasonable. A reasonable tradeoff value is 2.0. A value of 0.0 effective disables steering away from obstacles and acts like a naive binary search A*.
# use_final_approach_orientation: true # Whether to set the final path pose at the goal's orientation to the requested orientation (false) or in line with the approach angle so the robot doesn't rotate to heading (true)
# smoother:
# max_iterations: 1000
# w_smooth: 0.3
# w_data: 0.2
# tolerance: 0.1
planner_server:
ros__parameters:
planner_plugins: ["GridBased"]
use_sim_time: True
GridBased:
plugin: "nav2_smac_planner/SmacPlanner2D"
tolerance: 0.125 # tolerance for planning if unable to reach exact pose, in meters
downsample_costmap: false # whether or not to downsample the map
downsampling_factor: 1 # multiplier for the resolution of the costmap layer (e.g. 2 on a 5cm costmap would be 10cm)
allow_unknown: true # allow traveling in unknown space
max_iterations: 1000000 # maximum total iterations to search for before failing (in case unreachable), set to -1 to disable
max_on_approach_iterations: 1000 # maximum number of iterations to attempt to reach goal once in tolerance
max_planning_time: 2.0 # max time in s for planner to plan, smooth
cost_travel_multiplier: 2.0 # Cost multiplier to apply to search to steer away from high cost areas. Larger values will place in the center of aisles more exactly (if non-`FREE` cost potential field exists) but take slightly longer to compute. To optimize for speed, a value of 1.0 is reasonable. A reasonable tradeoff value is 2.0. A value of 0.0 effective disables steering away from obstacles and acts like a naive binary search A*.
use_final_approach_orientation: true # Whether to set the final path pose at the goal's orientation to the requested orientation (false) or in line with the approach angle so the robot doesn't rotate to heading (true)
plugin: "nav2_smac_planner/SmacPlannerHybrid"
downsample_costmap: false # whether or not to downsample the map
downsampling_factor: 1 # multiplier for the resolution of the costmap layer (e.g. 2 on a 5cm costmap would be 10cm)
tolerance: 0.25 # dist-to-goal heuristic cost (distance) for valid tolerance endpoints if exact goal cannot be found.
allow_unknown: true # allow traveling in unknown space
max_iterations: 1000000 # maximum total iterations to search for before failing (in case unreachable), set to -1 to disable
max_on_approach_iterations: 1000 # Maximum number of iterations after within tolerances to continue to try to find exact solution
max_planning_time: 5.0 # max time in s for planner to plan, smooth
motion_model_for_search: "DUBIN" # Hybrid-A* Dubin, Redds-Shepp
angle_quantization_bins: 72 # Number of angle bins for search
analytic_expansion_ratio: 3.5 # The ratio to attempt analytic expansions during search for final approach.
analytic_expansion_max_length: 3.0 # For Hybrid/Lattice nodes: The maximum length of the analytic expansion to be considered valid to prevent unsafe shortcutting
analytic_expansion_max_cost: true # The maximum single cost for any part of an analytic expansion to contain and be valid, except when necessary on approach to goal
analytic_expansion_max_cost_override: false # Whether or not to override the maximum cost setting if within critical distance to goal (ie probably required)
minimum_turning_radius: 0.20 # was 0.40 # minimum turning radius in m of path / vehicle
reverse_penalty: 1.0 #was2.0 # Penalty to apply if motion is reversing, must be => 1
change_penalty: 0.0 # Penalty to apply if motion is changing directions (L to R), must be >= 0
non_straight_penalty: 2.0 #was 1.2 # Penalty to apply if motion is non-straight, must be => 1
cost_penalty: 2.0 # Penalty to apply to higher cost areas when adding into the obstacle map dynamic programming distance expansion heuristic. This drives the robot more towards the center of passages. A value between 1.3 - 3.5 is reasonable.
retrospective_penalty: 0.015
lookup_table_size: 20.0 # Size of the dubin/reeds-sheep distance window to cache, in meters.
cache_obstacle_heuristic: true #was false # Cache the obstacle map dynamic programming distance expansion heuristic between subsiquent replannings of the same goal location. Dramatically speeds up replanning performance (40x) if costmap is largely static.
debug_visualizations: false # For Hybrid nodes: Whether to publish expansions on the /expansions topic as an array of poses (the orientation has no meaning) and the path's footprints on the /planned_footprints topic. WARNING: heavy to compute and to display, for debug only as it degrades the performance.
use_quadratic_cost_penalty: True #was False
downsample_obstacle_heuristic: True
allow_primitive_interpolation: False
smooth_path: True # If true, does a simple and quick smoothing post-processing to the path
smoother:
max_iterations: 1000
w_smooth: 0.3
w_data: 0.2
tolerance: 0.1
tolerance: 1.0e-10
do_refinement: true
refinement_num: 2
smoother_server:
ros__parameters:

View File

@ -61,6 +61,7 @@ services:
- ${XAUTHORITY:-$HOME/.Xauthority}:/root/.Xauthority
- ./config/entrypoint.sh:/entrypoint.sh
- ./config/cyclonedds.xml:/cyclonedds.xml
restart: unless-stopped
# networks: # not using bridging anymore, instead try using all services on macvlan? let's see... shoudl word for now. Bridging does definitely not work because multicast is not supported here.
# rmp:
@ -150,7 +151,7 @@ services:
command: >
ros2 launch cps_rmp220_support robot_scan_filter.launch.py
# localiaztion by ekf node
# localization by ekf node
ekf:
extends: overlay
depends_on:
@ -200,7 +201,7 @@ services:
- ekf
- oakd
command: >
ros2 launch nav2_bringup bringup_launch.py slam:=True map:=/repo/maps/map.yaml use_sim_time:=False use_composition:=True params_file:=/repo/config/nav2_params.yaml
ros2 launch nav2_bringup bringup_launch.py slam:=False map:=/repo/maps/map_01-26-24.yaml use_sim_time:=False use_composition:=True params_file:=/repo/config/nav2_params.yaml
#maps/map_openlabday.yaml
# bash
bash:
@ -233,6 +234,9 @@ services:
extends: overlay
command: >
ros2 launch foxglove_bridge foxglove_bridge_launch.xml port:=8765
#tls:=true certfile:=/certs/foxgloveCert.crt keyfile:=/certs/foxgloveKey.key
volumes:
- /opt/cps/certs:/certs
# Foxglove Studio Webserver
foxglove:
@ -327,9 +331,9 @@ services:
# In order to connect to the ROS-master, we execute locally on robot2:
# export ROS_MASTER_URI=http://192.1.1.1:11311
# export ROS_IP=192.168.1.2
# export ROS_HOSTNAME=192.168.1.2
# export ROS_MASTER_URI=http://192.168.0.100:11311
# export ROS_IP=192.168.0.?
# export ROS_HOSTNAME=192.168.1.?
# ROS2 oak-d-lite camera
oakd:

7
maps/map_01-26-24.yaml Normal file
View File

@ -0,0 +1,7 @@
image: map_01-26-24.pgm
mode: trinary
resolution: 0.02
origin: [-4, -14.8, 0]
negate: 0
occupied_thresh: 0.65
free_thresh: 0.25