This commit is contained in:
Björn Ellensohn 2024-01-25 10:13:50 +01:00
commit 90639412ef
22 changed files with 921 additions and 163 deletions

1
.gitignore vendored Normal file
View File

@ -0,0 +1 @@
*.pgm

29
cert.pem Normal file
View File

@ -0,0 +1,29 @@
-----BEGIN CERTIFICATE-----
MIIFCTCCAvGgAwIBAgIUSToN1sKvyyEHUX43N0x2pJ2tozYwDQYJKoZIhvcNAQEL
BQAwFDESMBAGA1UEAwwJbG9jYWxob3N0MB4XDTIzMDgyMzE0NDgwMFoXDTI0MDgy
MjE0NDgwMFowFDESMBAGA1UEAwwJbG9jYWxob3N0MIICIjANBgkqhkiG9w0BAQEF
AAOCAg8AMIICCgKCAgEAuz16ToP/oe0GlHELnOxXVMbQ4ygDhAoJRDW+h3AN01QP
GD8hKByM5QKUd1bnUa40jKeENerJLVpwvYW+wksIw8OEoU+XKLQav59LkumMx94Y
92vhfYPEdjJGfBSemf4GALw0GmeizeglGKQAomBN2fV0Wege77T6aE3GSafzmgWk
WKIXLzYd0C+fzMUnf7TtbpacG71D1VAryedq2/srR6ZnrP92SyWB6vJt9kdFxhie
V0zdrmiLhKbj4QBHn2ZfBzBe33eLHEJc7DlQ7fkQr58PVnF35h0lIYC2YdZjGSIe
1r12HGCvjDlDX3ygznsnMIIOGPd78vzpiVUlIk1MLqS4FeAMqyTFuljZ7UjG2+Yf
p+9gJ/3vfbCiWmtwJOuZvCeXvCwUGlvJH7aFan9UKG0OCuIOBY+8ZqkbgKQ8lCNv
hk5HD8z49pa2u9Tzau68KMLOIhJ000sPW17RrWTrQK0izLeNmxlUvNFtg65pCpE7
yUinlKVfBjPraK1htuZL/E0MZ1sq9YV/VbjFQnrhad1bZ+DvLRuX2Ehd8gsUt6UL
hQW3vq7GmXo0u+xT1XIkCEYdNUGo4xXKr925MmcRVa6gR5dsAuAoQ5cN/5z4wnJt
eNonakERtPomAC/ACTsbr3RjpG6h0jPHXta5XC+PKydV9riuk/LAIRIF0dKGfHUC
AwEAAaNTMFEwHQYDVR0OBBYEFKL/qoyl0fc1f6VBhW5GJDpae5a7MB8GA1UdIwQY
MBaAFKL/qoyl0fc1f6VBhW5GJDpae5a7MA8GA1UdEwEB/wQFMAMBAf8wDQYJKoZI
hvcNAQELBQADggIBADoEzbUqOiTbTOppCRP3q+l8Z3mlymtZgz/BcyGms+8B2LMC
xSJ88+lkg23XG8KQ+oIOHDaLBsVUePeSLLt3MAtDMbBEDUsUf2nWK+l3IbNlMxTn
1beb/FM1QRwLfbqGvVi7afpZvLH7wJc2SCv+996eW/Hau5yDxntqupjAd1G7pDrJ
PQMJhmWg1VQHxBC1MyMVdz8r4nqBSIKN5XMxdrZitXOa6c2b2/SvolGN6UEUD1at
LAbS1nXloBNVuOrmTCxRxCKxec8+2qs4QOc/Ux7jF9Q65TkW1IkucnDaOluDcufY
n4GQXaRFyQJInoGpWlOM3hJ2ZlhlQj+tjuvTyu7uWCINC4r0bYqpIpY4mWzXKRFT
e5M4nVy8YukjsM82zZRvXdD8Mlfuxb8xkpQBdqVClO24TSjZOCAw4qsizpV/N7S9
NmQ5+2CI4l3KvhH1gAjtXvNOOicn7laXDtz5wc1fZxmUptQQp5JXFtSguLpJpGli
r7s8wRPnVJW3HhjNIzYIzOm3J4dtl1+ZqHGfeFes+8ty2HAJK1AmnRvt8UQK3VjR
YrlzbM6+cjzmJQ3S3LTXOi0Zssf6SQspCaAMP8hUXhZyi8y7PMNHpp/LuUEFox03
/L8X5DB9SXofdFp+1jVh6WZCV8wt39Fxo+l+5afpeIc138XOkgvsrBFNzTi9
-----END CERTIFICATE-----

21
config/cyclonedds.xml Normal file
View File

@ -0,0 +1,21 @@
<?xml version="1.0" encoding="UTF-8" ?>
<CycloneDDS xmlns="https://cdds.io/config" xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" xsi:schemaLocation="https://cdds.io/config https://raw.githubusercontent.com/eclipse-cyclonedds/cyclonedds/master/etc/cyclonedds.xsd">
<Domain id="any">
<General>
<Interfaces>
<NetworkInterface name="tailscale0"/>
</Interfaces>
<AllowMulticast>true</AllowMulticast>
</General>
<Discovery>
<Peers>
</Peers>
<ParticipantIndex>auto</ParticipantIndex>
<MaxAutoParticipantIndex>40</MaxAutoParticipantIndex>
</Discovery>
<Tracing>
<Verbosity>severe</Verbosity>
<OutputFile>stdout</OutputFile>
</Tracing>
</Domain>
</CycloneDDS>

98
config/entrypoint.sh Executable file
View File

@ -0,0 +1,98 @@
#!/bin/bash
# Basic entrypoint for ROS / Colcon Docker containers
UNDERLAY_WS=/rmp_ws
# Source ROS 2
source /opt/ros/${ROS_DISTRO}/setup.bash
echo "Sourced ROS 2 ${ROS_DISTRO}"
# Source the base workspace, if built
if [ -f ${UNDERLAY_WS}/install/setup.bash ]
then
source ${UNDERLAY_WS}/install/setup.bash
vcs pull ${UNDERLAY_WS}/src
echo "Sourced CPS RMP 220 base workspace"
fi
# Source the overlay workspace, if built
if [ -f /overlay_ws/install/setup.bash ]
then
source /overlay_ws/install/setup.bash
vcs pull /overlay_ws/src
echo "Sourced CPS RMP 220 Overlay workspace"
fi
# Source the bridge workspace, if built
if [ -f ~/ros2_humble/install/setup.bash ]
then
source ~/ros2_humbleinstall/setup.bash
#export GAZEBO_MODEL_PATH=$GAZEBO_MODEL_PATH:$(ros2 pkg prefix turtlebot3_gazebo)/share/turtlebot3_gazebo/models
echo "Sourced CPS RMP 220 base workspace"
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 ]
# 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
# 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
# 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 "$@"

506
config/nav2_params.yaml Normal file
View File

@ -0,0 +1,506 @@
slam_toolbox:
ros__parameters:
# Plugin params
solver_plugin: solver_plugins::CeresSolver
ceres_linear_solver: SPARSE_NORMAL_CHOLESKY
ceres_preconditioner: SCHUR_JACOBI
ceres_trust_strategy: LEVENBERG_MARQUARDT
ceres_dogleg_type: TRADITIONAL_DOGLEG
ceres_loss_function: None
# ROS Parameters
odom_frame: odom
map_frame: map
base_frame: base_footprint
#scan_topic: /scan
scan_topic: /scan_filtered
use_map_saver: true
mode: mapping #localization
# if you'd like to immediately start continuing a map at a given pose
# or at the dock, but they are mutually exclusive, if pose is given
# will use pose
#map_file_name: test_steve
#map_start_pose: [0.0, 0.0, 0.0]
#map_start_at_dock: true
debug_logging: false
throttle_scans: 1
transform_publish_period: 0.02 #if 0 never publishes odometry
map_update_interval: 5.0
resolution: 0.02 # was 0.05 ; resolution equals to how many meters are 1 pixel on the map. So the lower value the higher the resoltion
max_laser_range: 20.0 #for rastering images
minimum_time_interval: 0.5
transform_timeout: 0.2
tf_buffer_duration: 30.
stack_size_to_use: 40000000 #// program needs a larger stack size to serialize large maps
enable_interactive_mode: true
# General Parameters
use_scan_matching: true
use_scan_barycenter: true
minimum_travel_distance: 0.5
minimum_travel_heading: 0.5
scan_buffer_size: 10
scan_buffer_maximum_scan_distance: 10.0
link_match_minimum_response_fine: 0.1
link_scan_maximum_distance: 1.5
loop_search_maximum_distance: 3.0
do_loop_closing: true
loop_match_minimum_chain_size: 10
loop_match_maximum_variance_coarse: 3.0
loop_match_minimum_response_coarse: 0.35
loop_match_minimum_response_fine: 0.45
# Correlation Parameters - Correlation Parameters
correlation_search_space_dimension: 0.5
correlation_search_space_resolution: 0.01
correlation_search_space_smear_deviation: 0.1
# Correlation Parameters - Loop Closure Parameters
loop_search_space_dimension: 8.0
loop_search_space_resolution: 0.05
loop_search_space_smear_deviation: 0.03
# Scan Matcher Parameters
distance_variance_penalty: 0.5
angle_variance_penalty: 1.0
fine_search_angle_offset: 0.00349
coarse_search_angle_offset: 0.349
coarse_angle_resolution: 0.0349
minimum_angle_penalty: 0.9
minimum_distance_penalty: 0.5
use_response_expansion: true
amcl:
ros__parameters:
use_sim_time: True
alpha1: 0.2
alpha2: 0.2
alpha3: 0.2
alpha4: 0.2
alpha5: 0.2
base_frame_id: "base_footprint"
beam_skip_distance: 0.5
beam_skip_error_threshold: 0.9
beam_skip_threshold: 0.3
do_beamskip: false
global_frame_id: "map"
lambda_short: 0.1
laser_likelihood_max_dist: 2.0
laser_max_range: 7.0 #was 100.0
laser_min_range: -1.0
laser_model_type: "likelihood_field"
max_beams: 60
max_particles: 2000
min_particles: 500
odom_frame_id: "odom"
pf_err: 0.05
pf_z: 0.99
recovery_alpha_fast: 0.0
recovery_alpha_slow: 0.0
resample_interval: 1
robot_model_type: "nav2_amcl::DifferentialMotionModel"
save_pose_rate: 0.5
sigma_hit: 0.2
tf_broadcast: true
transform_tolerance: 1.0
update_min_a: 0.2
update_min_d: 0.25
z_hit: 0.5
z_max: 0.05
z_rand: 0.5
z_short: 0.05
scan_topic: scan_filtered
bt_navigator:
ros__parameters:
use_sim_time: True
global_frame: map
robot_base_frame: base_link
odom_topic: /odometry/filtered
bt_loop_duration: 10
default_server_timeout: 20
# 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults:
# nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml
# nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml
# They can be set here or via a RewrittenYaml remap from a parent launch file to Nav2.
plugin_lib_names:
- nav2_compute_path_to_pose_action_bt_node
- nav2_compute_path_through_poses_action_bt_node
- nav2_smooth_path_action_bt_node
- nav2_follow_path_action_bt_node
- nav2_spin_action_bt_node
- nav2_wait_action_bt_node
- nav2_assisted_teleop_action_bt_node
- nav2_back_up_action_bt_node
- nav2_drive_on_heading_bt_node
- nav2_clear_costmap_service_bt_node
- nav2_is_stuck_condition_bt_node
- nav2_goal_reached_condition_bt_node
- nav2_goal_updated_condition_bt_node
- nav2_globally_updated_goal_condition_bt_node
- nav2_is_path_valid_condition_bt_node
- nav2_initial_pose_received_condition_bt_node
- nav2_reinitialize_global_localization_service_bt_node
- nav2_rate_controller_bt_node
- nav2_distance_controller_bt_node
- nav2_speed_controller_bt_node
- nav2_truncate_path_action_bt_node
- nav2_truncate_path_local_action_bt_node
- nav2_goal_updater_node_bt_node
- nav2_recovery_node_bt_node
- nav2_pipeline_sequence_bt_node
- nav2_round_robin_node_bt_node
- nav2_transform_available_condition_bt_node
- nav2_time_expired_condition_bt_node
- nav2_path_expiring_timer_condition
- nav2_distance_traveled_condition_bt_node
- nav2_single_trigger_bt_node
- nav2_goal_updated_controller_bt_node
- nav2_is_battery_low_condition_bt_node
- nav2_navigate_through_poses_action_bt_node
- nav2_navigate_to_pose_action_bt_node
- nav2_remove_passed_goals_action_bt_node
- nav2_planner_selector_bt_node
- nav2_controller_selector_bt_node
- nav2_goal_checker_selector_bt_node
- nav2_controller_cancel_bt_node
- nav2_path_longer_on_approach_bt_node
- nav2_wait_cancel_bt_node
- nav2_spin_cancel_bt_node
- nav2_back_up_cancel_bt_node
- nav2_assisted_teleop_cancel_bt_node
- nav2_drive_on_heading_cancel_bt_node
- nav2_is_battery_charging_condition_bt_node
bt_navigator_navigate_through_poses_rclcpp_node:
ros__parameters:
use_sim_time: True
bt_navigator_navigate_to_pose_rclcpp_node:
ros__parameters:
use_sim_time: True
# 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.1
# 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", "ObstacleFootprint", "PreferForward"]
# 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
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
local_costmap:
local_costmap:
ros__parameters:
update_frequency: 5.0
publish_frequency: 2.0
global_frame: odom
robot_base_frame: base_link
use_sim_time: True
rolling_window: true
width: 3
height: 3
resolution: 0.02 # was 0.05 ; this param control the resolution how many meters is 1 pixel on the map
#robot_radius: 0.22
footprint: "[ [0.18, 0.200], [0.18, -0.200], [-0.54, -0.165], [-0.54, 0.165] ]" # gave another points for the polygon "[ [0.18, 0.255], [0.18, -0.255], [-0.54, -0.165], [-0.54, 0.165] ]"
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.
voxel_layer:
plugin: "nav2_costmap_2d::VoxelLayer"
enabled: True
publish_voxel_map: True
origin_z: 0.0
z_resolution: 0.05
z_voxels: 16
max_obstacle_height: 2.0
mark_threshold: 0
observation_sources: rplidar oakd
rplidar:
topic: /scan_filtered
max_obstacle_height: 2.0
clearing: True
marking: True
data_type: "LaserScan"
raytrace_max_range: 3.0
raytrace_min_range: 0.0
obstacle_max_range: 2.5
obstacle_min_range: 0.0
oak-d: # no frame set, uses frame from message
topic: /stereo/points
max_obstacle_height: 1.5
min_obstacle_height: 0.02
obstacle_max_range: 3.0
obstacle_min_range: 0.0
raytrace_max_range: 3.2
raytrace_min_range: 0.0
clearing: True
marking: True
data_type: "PointCloud2"
static_layer:
plugin: "nav2_costmap_2d::StaticLayer"
map_subscribe_transient_local: True
always_send_full_costmap: True
global_costmap:
global_costmap:
ros__parameters:
update_frequency: 1.0
publish_frequency: 1.0
global_frame: map
robot_base_frame: base_link
use_sim_time: True
#robot_radius: 0.22
footprint: "[ [0.18, 0.255], [0.18, -0.255], [-0.54, -0.165], [-0.54, 0.165] ]" # gave another points for the polygon
resolution: 0.05
track_unknown_space: true
plugins: ["static_layer", "obstacle_layer", "inflation_layer"]
obstacle_layer:
plugin: "nav2_costmap_2d::ObstacleLayer"
enabled: True
observation_sources: scan
scan:
topic: /scan_filtered
max_obstacle_height: 2.0
clearing: True
marking: True
data_type: "LaserScan"
raytrace_max_range: 3.0
raytrace_min_range: 0.0
obstacle_max_range: 2.5
obstacle_min_range: 0.0
static_layer:
plugin: "nav2_costmap_2d::StaticLayer"
map_subscribe_transient_local: True
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
cost_scaling_factor: 10.0 # was 3.0
inflation_radius: 0.55
always_send_full_costmap: True
map_server:
ros__parameters:
use_sim_time: True
# Overridden in launch by the "map" launch configuration or provided default value.
# To use in yaml, remove the default "map" value in the tb3_simulation_launch.py file & provide full path to map below.
yaml_filename: ""
map_saver:
ros__parameters:
use_sim_time: True
save_map_timeout: 5.0
free_thresh_default: 0.25
occupied_thresh_default: 0.65
map_subscribe_transient_local: True
# planner_server:
# ros__parameters:
# expected_planner_frequency: 20.0
# use_sim_time: True
# planner_plugins: ["GridBased"]
# GridBased:
# plugin: "nav2_navfn_planner/NavfnPlanner"
# 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
smoother_server:
ros__parameters:
use_sim_time: True
smoother_plugins: ["simple_smoother"]
simple_smoother:
plugin: "nav2_smoother::SimpleSmoother"
tolerance: 1.0e-10
max_its: 1000
do_refinement: True
behavior_server:
ros__parameters:
costmap_topic: local_costmap/costmap_raw
footprint_topic: local_costmap/published_footprint
cycle_frequency: 10.0
behavior_plugins: ["spin", "backup", "drive_on_heading", "assisted_teleop", "wait"]
spin:
plugin: "nav2_behaviors/Spin"
backup:
plugin: "nav2_behaviors/BackUp"
drive_on_heading:
plugin: "nav2_behaviors/DriveOnHeading"
wait:
plugin: "nav2_behaviors/Wait"
assisted_teleop:
plugin: "nav2_behaviors/AssistedTeleop"
global_frame: odom
robot_base_frame: base_link
transform_tolerance: 0.1
use_sim_time: true
simulate_ahead_time: 2.0
max_rotational_vel: 1.0
min_rotational_vel: 0.4
rotational_acc_lim: 3.2
robot_state_publisher:
ros__parameters:
use_sim_time: True
waypoint_follower:
ros__parameters:
use_sim_time: True
loop_rate: 20
stop_on_failure: false
waypoint_task_executor_plugin: "wait_at_waypoint"
wait_at_waypoint:
plugin: "nav2_waypoint_follower::WaitAtWaypoint"
enabled: True
waypoint_pause_duration: 200
velocity_smoother:
ros__parameters:
use_sim_time: True
smoothing_frequency: 20.0
scale_velocities: False
feedback: "CLOSED_LOOP" # was OPEN_LOOP
max_velocity: [0.26, 0.0, 1.0]
min_velocity: [-0.26, 0.0, -1.0]
max_accel: [2.5, 0.0, 3.2]
max_decel: [-2.5, 0.0, -3.2]
odom_topic: "/odometry/filtered"
odom_duration: 0.1 # was 0.1
deadband_velocity: [0.0, 0.0, 0.0]
velocity_timeout: 1.0

View File

@ -20,6 +20,9 @@ networks:
# config:
# - subnet:
# add this mountpoint to all services: - ./customize/entrypoint.sh:/entrypoint.sh
# Attention: child services will inherit settings from their parents. So if you set a network_mode: host in the base service, all child services will also use host networking. This is not always what you want. So be careful with this.
services:
# Base image containing dependencies.
base:
@ -36,7 +39,6 @@ services:
platforms:
- linux/arm64
- linux/amd64
# Interactive shell
stdin_open: true
tty: true
@ -44,16 +46,21 @@ services:
network_mode: host
ipc: host
# Needed to display graphical applications
#privileged: true
environment:
# Allows graphical programs in the container.
- DISPLAY=${DISPLAY}
- QT_X11_NO_MITSHM=1
- NVIDIA_DRIVER_CAPABILITIES=all
# set correct ros2 parameters: domain id and rmw implementation
- ROS_DOMAIN_ID=5
- RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
- CYCLONEDDS_URI=file:///cyclonedds.xml
volumes:
# Allows graphical programs in the container.
- /tmp/.X11-unix:/tmp/.X11-unix:rw
- ${XAUTHORITY:-$HOME/.Xauthority}:/root/.Xauthority
- ./config/entrypoint.sh:/entrypoint.sh
- ./config/cyclonedds.xml:/cyclonedds.xml
# 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:
@ -92,23 +99,16 @@ services:
platforms:
- linux/arm64
- linux/amd64
#entrypoint: /bin/bash
command: >
/bin/bash
devices:
- /dev/dri:/dev/dri
# Robot State Publisher
rsp:
extends: overlay
command: >
ros2 launch cps_rmp220_support rsp.launch.py
stdin_open: true
tty: true
# Networking and IPC for ROS 2
#network_mode: host
ipc: host
environment:
- ROS_DOMAIN_ID=5
- RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
# Controller
controller:
@ -116,21 +116,9 @@ services:
command: >
ros2 run segwayrmp SmartCar --ros-args -r cmd_vel:=cmd_vel_out -p serial_full_name:=/dev/segway
devices:
- /dev/segway:/dev/segway
- /dev/ttyUSB0:/dev/ttyUSB0
# Interactive shell
stdin_open: true
tty: true
# Networking and IPC for ROS 2
#network_mode: host
ipc: host
# Needed to display graphical applications
privileged: false
# depends_on:
# - robot_state_publisher
environment:
- ROS_DOMAIN_ID=5
- RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
- /dev/segway:/dev/ttyUSB0
#- /dev/ttyUSB0:/dev/ttyUSB0
privileged: true
# teleop
teleop:
@ -141,17 +129,8 @@ services:
ros2 launch rmp220_teleop robot_joystick.launch.py
devices:
- /dev/input/js0:/dev/input/js0
# Interactive shell
stdin_open: true
tty: true
# Networking and IPC for ROS 2
#network_mode: host
ipc: host
# Needed to display graphical applications
#- /dev/input/by-id/usb-Logitech_Wireless_Gamepad_F710_56679674-joystick:/dev/input/by-id/usb-Logitech_Wireless_Gamepad_F710_56679674-joystick
privileged: true
environment:
- ROS_DOMAIN_ID=5
- RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
# lidar
lidar:
@ -160,16 +139,6 @@ services:
- lidar_filter
command: >
ros2 launch cps_rmp220_support robot_lidar.launch.py serial_port:=/dev/rplidarA1
stdin_open: true
tty: true
# Networking and IPC for ROS 2
#network_mode: host
ipc: host
# depends_on:
# - robot_state_publisher
environment:
- ROS_DOMAIN_ID=5
- RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
devices:
- /dev/rplidarA1:/dev/rplidarA1 #udevrules needed for this to work:
# SUBSYSTEM=="tty", ATTRS{serial}=="0001", SYMLINK+="segway"
@ -180,14 +149,6 @@ services:
extends: overlay
command: >
ros2 launch cps_rmp220_support robot_scan_filter.launch.py
stdin_open: true
tty: true
# Networking and IPC for ROS 2
#network_mode: host
ipc: host
environment:
- ROS_DOMAIN_ID=5
- RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
# localiaztion by ekf node
ekf:
@ -197,15 +158,6 @@ services:
- rsp
command: >
ros2 launch cps_rmp220_support robot_localization.launch.py
# Interactive shell
stdin_open: true
tty: true
# Networking and IPC for ROS 2
#network_mode: host
ipc: host
environment:
- ROS_DOMAIN_ID=5
- RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
# mapping
mapping:
@ -216,15 +168,6 @@ services:
- lidar
command: >
ros2 launch cps_rmp220_support robot_mapping.launch.py
# Interactive shell
stdin_open: true
tty: true
# Networking and IPC for ROS 2
#network_mode: host
ipc: host
environment:
- ROS_DOMAIN_ID=5
- RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
# slam-toolbox-localization
localization:
@ -235,15 +178,6 @@ services:
- lidar
command: >
ros2 launch cps_rmp220_support robot_mapping_localization.launch.py map_file_name:=/repo/maps/map.yaml
# Interactive shell
stdin_open: true
tty: true
# Networking and IPC for ROS 2
#network_mode: host
ipc: host
environment:
- ROS_DOMAIN_ID=5
- RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
# amcl_localization
amcl:
@ -254,15 +188,6 @@ services:
- lidar
command: >
ros2 launch cps_rmp220_support robot_amcl.launch.py map:=/repo/maps/map.yaml
# Interactive shell
stdin_open: true
tty: true
# Networking and IPC for ROS 2
#network_mode: host
ipc: host
environment:
- ROS_DOMAIN_ID=5
- RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
# navigation
navigation:
@ -274,52 +199,23 @@ services:
- lidar
- ekf
- oakd
# command: >
# ros2 launch cps_rmp220_support robot_navigation.launch.py
# map_subscribe_transient_local:=true
# command: >
# ros2 launch nav2_bringup bringup_launch.py slam:=True map:=/repo/maps/map_current.sav.yaml use_sim_time:=False use_composition:=True params_file:=/overlay_ws/src/cps_rmp220_support/config/nav2_params.yaml
command: >
ros2 launch nav2_bringup bringup_launch.py slam:=False map:=/repo/maps/map.yaml use_sim_time:=False use_composition:=True params_file:=/overlay_ws/src/cps_rmp220_support/config/nav2_params.yaml
stdin_open: true
tty: true
# Networking and IPC for ROS 2
#network_mode: host
ipc: host
environment:
- ROS_DOMAIN_ID=5
- RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
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
#maps/map_openlabday.yaml
# bash
bash:
extends: overlay
command: >
/bin/bash
stdin_open: true
tty: true
# Networking and IPC for ROS 2
#network_mode: host
ipc: host
environment:
- ROS_DOMAIN_ID=5
- RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
# rviz2
rviz2:
#extends: guis
image: ghcr.io/bjoernellens1/ros2_rmp/rmp:guis
# command: >
# ros2 launch cps_rmp220_support robot_rviz2.launch.py
command: >
ros2 launch cps_rmp220_support rviz.launch.py
# Interactive shell
stdin_open: true
tty: true
# Networking and IPC for ROS 2
network_mode: host
ipc: host
# Needed to display graphical applications
privileged: true
privileged: true # really necessary?
environment:
# Allows graphical programs in the container.
- DISPLAY=${DISPLAY}
@ -337,21 +233,9 @@ services:
extends: overlay
command: >
ros2 launch foxglove_bridge foxglove_bridge_launch.xml port:=8765
stdin_open: true
tty: true
# Networking and IPC for ROS 2
#network_mode: host
ipc: host
environment:
- ROS_DOMAIN_ID=5
- RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
# 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:
# ipv4_address: 192.168.0.201 #actually don't need to set ips. they are set automatically by docker-compose. SHould be inherited by all child services.
# Foxglove Studio Webserver
foxglove_webserver:
foxglove:
image: ghcr.io/foxglove/studio:latest
stdin_open: true
tty: true
@ -369,14 +253,6 @@ services:
extends: overlay
command: >
ros2 run ros2_cam_openCV cam_node
stdin_open: true
tty: true
# Networking and IPC for ROS 2
#network_mode: host
ipc: host
environment:
- ROS_DOMAIN_ID=5
- RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
devices:
- /dev/video0:/dev/video0
@ -393,14 +269,6 @@ services:
- navigation
command: >
ros2 launch cps_rmp220_support robot_exploration.launch.py
stdin_open: true
tty: true
# Networking and IPC for ROS 2
#network_mode: host
ipc: host
environment:
- ROS_DOMAIN_ID=5
- RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
### Images for ROS1 Interactions
#ROS1 Bridge
@ -440,21 +308,34 @@ services:
- RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
- ROS_MASTER_URI=http://localhost:11311 # is configured to run roscore on the robot but could change to local ros1 machine here
## Configure on ROS1 Hosts
# seggy 192.168.0.100
# locally running ros-package: control1
# subscribing topic2
# publishing topic1
# robot2 192.168.x.x
# locally running ros-package: control2
# subscribing topic1
# publishing topic2
# As we need one ros-master to control the communication, we choose 192.168.1.1 as master. Therefore we execute locally on robot 1:
# export ROS_MASTER_URI=http://192.168.0.100:11311 # or localhost?
# export ROS_HOSTNAME=192.168.0.100
# export ROS_IP=192.168.0.100
# roscore
# 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
# ROS2 oak-d-lite camera
oakd:
extends: overlay
command: >
ros2 launch depthai_examples stereo.launch.py
stdin_open: true
tty: true
# Networking and IPC for ROS 2
network_mode: host
ipc: host
environment:
- ROS_DOMAIN_ID=5
- RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
#privileged: true
#devices:
#- /dev/oakd-lite:/dev/oakd-lite # need corresponding udevrules for this to work:
# SUBSYSTEM=="usb", ATTRS{idVendor}=="03e7", MODE="0666", SYMLINK+="oakd-lite"
@ -463,7 +344,6 @@ services:
- 'c 189:* rmw'
volumes:
- /dev/bus/usb:/dev/bus/usb
# for testing the oak-d-lite camera -> works now with cgroup rules
depthai:
@ -481,3 +361,24 @@ services:
- QT_X11_NO_MITSHM=1
- NVIDIA_DRIVER_CAPABILITIES=all
zerotier:
image: "zyclonite/zerotier:router"
container_name: zerotier-one
devices:
- /dev/net/tun
network_mode: host
volumes:
- '/var/lib/zerotier-one:/var/lib/zerotier-one'
cap_add:
- NET_ADMIN
- SYS_ADMIN
- NET_RAW
restart: unless-stopped
environment:
- TZ=Europe/Amsterdam
- PUID=1000
- PGID=1000
- ZEROTIER_ONE_LOCAL_PHYS=enp5s0 wlx00e04c5513fc # change for actual interfaces
- ZEROTIER_ONE_USE_IPTABLES_NFT=false
- ZEROTIER_ONE_GATEWAY_MODE=inbound # might change to both ways
#- ZEROTIER_ONE_NETWORK_IDS= # does not really do much?

62
husarnet.yaml Normal file
View File

@ -0,0 +1,62 @@
services:
### Husarnet VPN Container for remote access
husarnet:
image: husarnet/husarnet
restart: unless-stopped
volumes:
- /var/lib/husarnet # This will persist your Husarnet Client keys, thus IP of the container will be stable/the same between (re)boots
sysctls:
- net.ipv6.conf.all.disable_ipv6=0 # Husarnet is using IPv6 for the internal connections
cap_add:
- NET_ADMIN
devices:
- /dev/net/tun
env_file:
- ./husarnet/.env # create .env file in the same folder as Dockerfile and specify HOSTNAME and JOINCODE there
color_controller:
build:
dockerfile: husarnet/Dockerfile
volumes:
- ./husarnet/cyclonedds.xml:/cyclonedds.xml
command:
- bash
- -c
- |
export CYCLONEDDS_URI=file:///cyclonedds.xml
ros2 run my_demo_pkg color_controller
network_mode: service:husarnet
move_controller:
build:
dockerfile: husarnet/Dockerfile
volumes:
- ./husarnet/cyclonedds.xml:/cyclonedds.xml
command:
- bash
- -c
- |
export CYCLONEDDS_URI=file:///cyclonedds.xml
ros2 run my_demo_pkg move_controller
network_mode: service:husarnet
turtle_sim:
image: osrf/ros:galactic-desktop
privileged: true
environment:
# Allows graphical programs in the container.
- DISPLAY=${DISPLAY}
- QT_X11_NO_MITSHM=1
- NVIDIA_DRIVER_CAPABILITIES=all
volumes:
# Allows graphical programs in the container.
- /tmp/.X11-unix:/tmp/.X11-unix:rw
- ${XAUTHORITY:-$HOME/.Xauthority}:/root/.Xauthority
- ./husarnet/cyclonedds.xml:/cyclonedds.xml
command:
- bash
- -c
- |
export CYCLONEDDS_URI=file:///cyclonedds.xml
ros2 run turtlesim turtlesim_node
network_mode: service:husarnet # This is the most important line in this setup. This will put the Husarnet Client in the same network namespace as your app (in this example: turtle_sim)

52
key.pem Normal file
View File

@ -0,0 +1,52 @@
-----BEGIN PRIVATE KEY-----
MIIJQgIBADANBgkqhkiG9w0BAQEFAASCCSwwggkoAgEAAoICAQC7PXpOg/+h7QaU
cQuc7FdUxtDjKAOECglENb6HcA3TVA8YPyEoHIzlApR3VudRrjSMp4Q16sktWnC9
hb7CSwjDw4ShT5cotBq/n0uS6YzH3hj3a+F9g8R2MkZ8FJ6Z/gYAvDQaZ6LN6CUY
pACiYE3Z9XRZ6B7vtPpoTcZJp/OaBaRYohcvNh3QL5/MxSd/tO1ulpwbvUPVUCvJ
52rb+ytHpmes/3ZLJYHq8m32R0XGGJ5XTN2uaIuEpuPhAEefZl8HMF7fd4scQlzs
OVDt+RCvnw9WcXfmHSUhgLZh1mMZIh7WvXYcYK+MOUNffKDOeycwgg4Y93vy/OmJ
VSUiTUwupLgV4AyrJMW6WNntSMbb5h+n72An/e99sKJaa3Ak65m8J5e8LBQaW8kf
toVqf1QobQ4K4g4Fj7xmqRuApDyUI2+GTkcPzPj2lra71PNq7rwows4iEnTTSw9b
XtGtZOtArSLMt42bGVS80W2DrmkKkTvJSKeUpV8GM+torWG25kv8TQxnWyr1hX9V
uMVCeuFp3Vtn4O8tG5fYSF3yCxS3pQuFBbe+rsaZejS77FPVciQIRh01QajjFcqv
3bkyZxFVrqBHl2wC4ChDlw3/nPjCcm142idqQRG0+iYAL8AJOxuvdGOkbqHSM8de
1rlcL48rJ1X2uK6T8sAhEgXR0oZ8dQIDAQABAoICABwvlX1DRpSQEzj+SXK+aykS
YriHOfxC7IEtm/hUaGhjE4ChZDLfFWCWAlZyqRC1KijwQKlDJjSjFCybeQtTc0bQ
5GLKEeWpMwuchapgaPZfWx/HyCJ2Vvk5+T1Nd1CUGkA7FJbS+gGIDCmI6qWG3MFO
P00XcazA8B8Kcip9U2Dgr4w+HkJXoaZIvQP8u8TwLfvDRU2xsIfocScMJJxn02yO
QrYaoKqQQ13kT6ROt1SqOQ/IPOi3ySTXYJ9qxN1ccjqpT+bQ3oqK/OT8fc/M+fON
/KeVHijwQzonX40b0kAi0ESgMar07QgtSJSTtLtQc6ZMNaYRf0GlS9yGCjh/LVPo
IFCKjpSDfp2J9Q7RSFKdb8tghcTfQNAg/6zen1JnE5iUBiaQZfIj7+iD5hQfn9a2
I1Fs3m1or3n1Z+BUg7vkDPQCyRkVEBXkKsbpD3T2cnxY9sfF0+ClmdfBQyCcLG5p
mf6XAWQEiJrQ9iWuQYWpHDqaatan6G5ym8Wy7nJYdjJgJTszzduUSt176W8R7bGW
73y9de+kEODQsxehSpkTVEqsMEgpTAKi5u59RRhj4OT9Lbvk9Xs9OH23aUcVUu5H
urMIAKdsjlAUhLSPupDr4bJPRM9N4t2v709VeH170Z/9X5j7LbF++Wh2t+UXprmb
0nDk5fjfzJnjXJQgd+nRAoIBAQDpUc+3MuLadphfyM5b5xc9A/8TuwW5a2jcLi1h
6NlZa63qPbGvEk3kUw71ELrh8NorRqvn895CJUG4K+zVUTl9dgsXqla7GWZFHIXW
2641R4p8HQNwNFP7KIyvvv5l72A+wWf1jpZiXXYNinrHDtPgdVXEFMDhDLibu6AK
jsfdNOXDE+mmxMTSwwgJ9blZkdp1pBEWYCZsqW/yED6pLdTh8ZRPGHOb24x6HksZ
Z/Gc4SIOrj5jrt3/M9oEymP+fQnF/StlnVsRnai6hBQX9khlS3pjneLOCLJfhpt/
qcIDL03KsIhf0miIkOpNTATL4SGsWDBAQp17eN4UToacARRpAoIBAQDNcPlDVBqt
K+fy9BBR9HBzBQlx6XkrmZ9Cgje/FrpMT+2UZ5wqMMPyB7SdoXkxx0CpB3ajOost
i92fk7Y03xHXS3COGLKhWqDNhH1Uotlp3wpeOWx3DlAFRcIvy86iDzTa/hGaq8Kp
2HPw0YqcxQjwYQzILBfZx3DRuQ8bt3Wiqxer/K+NRDnass/ZUTqz6nZcadMj6NiS
Zlwm7ErjhjdYRc6amTZMtxOenxP8cAtNW+RBZ7JbUEhAhE8zU42wZI+DxhvM0mTg
/CrRaYVE6YyAnaYo0RuJCRldz6obbgABn0q8qoY1Rmxjm+Do27hsrQgAB9Z/gmAp
hdU2+S270fYtAoIBAQCuEYlEhkRU9HHN1ESQsCHYNakSEU+9+/JpglH9X/j4C6ve
vFRZ5vARzh20m9yxQD2kV79c98Xz11PmkW7J3yVjArRX3Y+DWvm/yf3YRGD+AvfA
jOzJw2B8Ws5LN9UYO7S0XRqwSsbLcCrpA02CQP+10BRCi7EytYjtNte5yLg3woVA
OxTwhJDLJRJUS+0SdAxmBBdzeBxyqR6Jm7EECttuDgu1zupBd1SgrwUcWT4a6qO8
DCcju4yIHykitdRQQv0Np0m/L9yHkfYV4QAUuHtehycyNtLFIBvjxMsyPXYvZhVF
iNrVkmbGrEcBkBtr9/RlXg3xg0F2osAcqlEnBm8xAoIBADGLZkGrfcd3iDeaTnlF
Rv0mINH86UDvim3is4j89S7EM9qPZiTyn761xwQg1faARAK/jwfsbXYtfeQnHlD/
3vCZ++n44NNy5MbLheIsZ9xVcs2ocZUAuaGb4iner9V7b1bE4P/5HjgRwFw6XIBU
MESwUwHPSG034OhjBda8Vr1FH69VgAzEgGNSrjeNlGehSqwcxVOqqtgboWutnp3i
V2SNaTb1bhfwKuYdHRfK+Z7NY222kVfeM56Digopw0jf55By7W9m6fcsOTNJjF9D
J6Q44MKFM2vH6vspwq9cxtmdTcvUIAunESqwg/wESSTEUeKYAU285m39HZ9lVncu
On0CggEAEk6pzS5OX7DSWqrTnYd9T83lr7RzFQpWpbeK7OOidMUYm/MHx7I2UyLN
V0K/ChkYowm69VvHJW9mcSHo0RAZiokBegJP8fhU0RJJaWyED+wdw2vOHlwAI7WP
hj3xCOT8D+qfx12wVqo6c0jRXnNUsd5V9DPtMkn7YFYuq56gSqwlLvIpuhfU8dJM
dCznLvjQqRQhqMk3p0bbcy4+EICR19F8UzgUfqWITwrdIriWQEWzDXIZvsBjxpaE
PenJGHMSac7xOU/hdljj6FSpwu03aA0HklCQhwpfNDd+KPR7ntNE1DBEn93/bScb
O61K2Igm/AywqweBe9cWRgB7lOXwIA==
-----END PRIVATE KEY-----

View File

@ -1,4 +1,4 @@
image: map_floor_mainb_full_save.pgm
image: map_floor_mainb_save_retouched.pgm
mode: trinary
resolution: 0.05
origin: [-66.2, -24.5, 0]

Binary file not shown.

View File

@ -0,0 +1,7 @@
image: map_floor_03-10-23.sav.pgm
mode: trinary
resolution: 0.05
origin: [-27.2, -0.0189, 0]
negate: 0
occupied_thresh: 0.65
free_thresh: 0.25

Binary file not shown.

Binary file not shown.

View File

@ -0,0 +1,7 @@
image: map_floor_mainb_save_retouched.pgm
mode: trinary
resolution: 0.05
origin: [-20.9, -7.03, 0]
negate: 0
occupied_thresh: 0.65
free_thresh: 0.25

File diff suppressed because one or more lines are too long

4
maps/map_openlabday.pgm Normal file

File diff suppressed because one or more lines are too long

7
maps/map_openlabday.yaml Normal file
View File

@ -0,0 +1,7 @@
image: map_openlabday.pgm
mode: trinary
resolution: 0.05
origin: [-13.5, -20.9, 0]
negate: 0
occupied_thresh: 0.65
free_thresh: 0.25

4
maps/map_save_16.10..pgm Normal file

File diff suppressed because one or more lines are too long

View File

@ -0,0 +1,7 @@
image: map_save_16.10..pgm
mode: trinary
resolution: 0.05
origin: [-25.7, -17, 0]
negate: 0
occupied_thresh: 0.65
free_thresh: 0.25

BIN
maps/map_ser_16.10..data Normal file

Binary file not shown.

Binary file not shown.

47
slim.report.json Normal file
View File

@ -0,0 +1,47 @@
{
"version": "1.1",
"engine": "linux|Transformer|1.40.6|1.40.6|latest",
"containerized": false,
"host_distro": {
"name": "NixOS",
"version": "23.11",
"display_name": "NixOS 23.11 (Tapir)"
},
"type": "build",
"state": "error",
"target_reference": "ubuntu",
"system": {
"type": "",
"release": "",
"distro": {
"name": "",
"version": "",
"display_name": ""
}
},
"source_image": {
"identity": {
"id": ""
},
"size": 0,
"size_human": "",
"create_time": "",
"docker_version": "",
"architecture": "",
"container_entry": {
"exe_path": ""
}
},
"minified_image_size": 0,
"minified_image_size_human": "",
"minified_image": "",
"minified_image_has_data": false,
"minified_by": 0,
"artifact_location": "",
"container_report_name": "",
"seccomp_profile_name": "",
"apparmor_profile_name": "",
"image_stack": null,
"image_created": false,
"image_build_engine": ""
}