From b6d09fe73a9e6cf57eef822acde0e288e1a66bcd Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Bj=C3=B6rn=20Ellensohn?= Date: Mon, 5 Feb 2024 12:00:26 +0100 Subject: [PATCH] update: added npm --- .gitignore | 4 +- config/box_filter.yaml | 27 ++ config/foxglove/index.html | 169 +++++++++++++ config/nav2_params.yaml | 504 +++++++++++++++++++++++++++++++++++++ config/npm/database.sqlite | Bin 0 -> 94208 bytes docker-compose.yaml | 34 ++- sudo | 1 - 7 files changed, 730 insertions(+), 9 deletions(-) create mode 100644 config/box_filter.yaml create mode 100644 config/foxglove/index.html create mode 100644 config/nav2_params.yaml create mode 100644 config/npm/database.sqlite delete mode 100644 sudo diff --git a/.gitignore b/.gitignore index 600d2d3..4d1c82f 100644 --- a/.gitignore +++ b/.gitignore @@ -1 +1,3 @@ -.vscode \ No newline at end of file +.vscode +config/npm/keys.json +config/npm/logs \ No newline at end of file diff --git a/config/box_filter.yaml b/config/box_filter.yaml new file mode 100644 index 0000000..ed930f3 --- /dev/null +++ b/config/box_filter.yaml @@ -0,0 +1,27 @@ +scan_to_scan_filter_chain: + ros__parameters: + filter1: + name: box_filter + type: laser_filters/LaserScanBoxFilter + params: + box_frame: laser_frame + max_x: 0.80 #was 0.16 + max_y: 0.18 #was 0.17 + max_z: 0.1 + min_x: -0.41 #was -0.41 + min_y: -0.18 # was -0.17 + min_z: -0.2 + invert: false # activate to remove all points outside of the box + name: shadows + type: laser_filters/ScanShadowsFilter + params: + min_angle: 10 + max_angle: 170 + neighbors: 20 + window: 1 + name: dark_shadows + type: laser_filters/LaserScanIntensityFilter + params: + lower_threshold: 100 + upper_threshold: 10000 + disp_histogram: 0 \ No newline at end of file diff --git a/config/foxglove/index.html b/config/foxglove/index.html new file mode 100644 index 0000000..f2d3df3 --- /dev/null +++ b/config/foxglove/index.html @@ -0,0 +1,169 @@ +Foxglove Studio
\ No newline at end of file diff --git a/config/nav2_params.yaml b/config/nav2_params.yaml new file mode 100644 index 0000000..0281cea --- /dev/null +++ b/config/nav2_params.yaml @@ -0,0 +1,504 @@ +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_filtered + 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: /home/bjorn/Documents/ros-projects/cps_bot_mini_ws/my_map_serial + # 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: 1.0 #was 5.0 + resolution: 0.05 + max_laser_range: 200.0 #for rastering images, standard was 20 + 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.05 + #robot_radius: 0.22 + footprint: "[ [0.065, 0.160], [0.065, -0.160], [-0.28, -0.13], [-0.28, 0.13] ]" # 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: 10.0 # was 3.0 + inflation_radius: 0.55 + 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.065, 0.160], [0.065, -0.160], [-0.28, -0.13], [-0.28, 0.13] ]" # 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 \ No newline at end of file diff --git a/config/npm/database.sqlite b/config/npm/database.sqlite new file mode 100644 index 0000000000000000000000000000000000000000..10726609860ed4a58f9d6b5c76377bce08e62466 GIT binary patch literal 94208 zcmeI5+i%?Xb;n7MMx&7|jlEuVuvjciPwdze-N?B}wy>LB?XJ=|vAs7t$vQAN9P%d( zB@Q_vIU1>k3ykD-E^RhIQ549fKwt6)#r}#~AdD!J&;o}p$ zY=_F(Sn}dU@rmMVMT;3sGt`pf`R$GAcRpNSySpykU3>f1x>RT%FG$x4rcsbg+h?21 zm2AhC?5br+71u0l?!L6m_9dtjuhGUMkR*<}*We?1E&_mT#6>`${@rb_{dF z93kM;Z04#}kG=+FPDz-aYA}mYE(6MDunnzh`O;PSDv26SSu<_b*2>H)NL!v`cb7$H zu1|&0sh9)vl6n*KJWC}T)Q^y_X6$M<397ndZBsL+ z#gYpP;*UQHbmlU{beZm(jvc5jynnV=gW=PsUXi4gn&uj6m%0nmuIB0`&Apb%=hJQU z#Jl1$GOk^wRy4o#R111`Hd3@4eOqOF70WSwvd+F{*0z$sl>fgb^+{|pmb`RH{K?0G zNmX2DZ$B`m&el|~8Ffy)Fa~5+hTBcc$SRKO_iKv`OVf4cd8%c4{!!e?v$HH+(@Unk zsWLlo`2B?qIkqp^66=Y0EO~QItgo21!S(`IUtw<9^gQn1nyz21+U8D`h0abkP4wQK zn;+a;mu}v9cl`%aAtV$^q9Bpm56f_qZst@-A3m6fCFkbECp$sg2qhQVjrX>a(Akq| zDy^FIIT13;UDGp*re*s3!)?3M)X5PIbDZIBWrS#Z3^78+^J%D19wE@xo<>M@HKSot z>BEUwEIB(Xe&V(D%ZW|&Yw~2&cZ?AY7d5@3wQEL$A8WWi`KV~bSySI0EurmdzUB^3 z!F8;@QCIpPKOU&!@$EnrG<+=a-&n6I_@R?g#i*9#?^n8jW#yh>g~w>J2(J)?0@`B3~fX_s@*;&Zsd?^LEH{Gu30%7t)L(v>WLuSm@+64r`vSOxIr* z1LHYZ8dU92bpw=`@}yc{vq+(#NW~`J|F-BAOHd&00JNY0w4eaAOHd&00Pg9z;rBf zQPir2>C@vNn~|5sBXjZ4LvXQZWHuf=)-y&M{Nzj|a!KqwX>snQGjvsFKX|YtDMs?~ z(BlTd2|oYl&*nEC&wpkWL&6{c0w4eaAOHd&00JNY0w4eaAOHdtK1{69(DPb?(HXZ|qr_cNc)JeavQBTRob{fp@`3E%?)AOHd&00JNY0w4eaAOHd{ zCV||!sG!E989AdUihNzkXe)nvM$h znmM$t%Jg2PmnfcC>w>@e`q`-PPH=%tndFpQ_IggC@J$qKhu>sw$^CV9Dk?l^$jLb_ zNpiB<6-GqWEtA5OsT<~A>!QC}nrxLuZe5hUG2o)s1)pAtM};+>i*iHGWLD(mysWIy zKj`~D#oX~)Vn4k!5fyH<#FXpuGB3MY^8B{QllfRwc&{yzSCl;AR`sgqJ7tQr(1`EQ zO7PFGjCb-?AydJXNH^!RER<4tc zWC=hne_bv4ekG%N)d~-F)Jk|K9f=Azn+fx}=QG*daywxjQLZJrb@fbCSZ|2RH!>ue z%PU#6#)=+~AJHMeE{jp&&8FZoK~nP9^RjB%rf+IiD>)7K|6fc8hFXIF2!H?xfB*=9 z00@8p2!H?xyf6gX_y5Jjj|KX{2LwO>1V8`;KmY_l00ck)1V8`;K;Rh@*cB&*Y&QN{ zJ$inEo+`;L$e9H>FDdeBUS7@SLx+}Evp4uN8a2l?E@z6DmF(rsZGEe}w)64kpRFk$ zrm+$3vbnRQW?w6INZ~bY0{nqlsM~(acw}r&* zXIw!f4+0Ol7ekZw0rPleHJdAL zIn1>enPoBCb4vDG^m1N{IYnkKYWgC*ezD@M8D)A8eDm+pQms~7q*qi1uLxb#o$^v+ zb4h2qLjRVrtm(^IKA+cDR*Vc|%Z!dOJ)>xEHvcK*jdJ;iDUGL@deE5v|3*ms=CmjQ z^#B17009sH0T2KI5C8!X009sHf#;OK$HB5f{K6~2=jqD|e5FCNtg>cnn{4#=Bq0$K z|0~cBJ|F-BAOHd&00JNY0w4eaAOHd&00O6wKqL~6^ZWn8xl>pW|{j=|UxW0CGUAnvW_N{fP5I$Xyt`$t9Aepw$Hkm8gjxX6&%aSUtS=QWrX`Ag! zTGe;xO$#n7Guxk+3bdv9%upS>AQ`mfn`PF%lFpYM!`v`O2skyHxoXv;uR)np5~imb z%wm+wfU-4T*dSe%uac=cg+pAcP=~Jcpw9}ii zX6$MFaa{kY`7xVY-bl?TJg<`H zd+HH{12qQ1UbWaz)YB{7Qmm(!$S#NIw4;K{4LM${)|I@{gv_9ehXc;anXBm^y)hX} zUb-ZHx*oK-itFs{2d%BMHPzeBIwwwh3rn?elJ`jsZCWj>8i0=_S+NJhI__>5Y|Q*g7?}#)=+!3FfQS3cdDbv=uj6*s&UUOJPTBU%WB##&v|| z9{2|Ga2oHlnlAg9dW&>D5sxKr&WZIE(>B;%(D785TQ)t9_nXa*NTpW{?NnLl>}0cH z-@9}3gL~`J%{%X||3E5)ghELaB#Ofv$PJVJ(#jc_4_pj|)i$l+`s8D@5ob+( zd$dI3jb6i3a2=~}446L1j|ZxFd^=DD4Q5OHH`c2Pe&}RWF{&l``;{(WS-EGl>Mlr-MJF4c>^$XF!Mb#e!+{z~PGJ(fd`RFvXJKjq(bT$CXJ@0^#)~JaFm6hk! zHPlSk7si62*uj-hsXAFkhn3}X>9^k^$$J&)1$3PW0v%}QuJXxHXIhl5ry{XrJ}=fc zgYs_MY)@?qH>x-2*jR5J28n!uP~Sf@&O4)zgCcr6QBZ+Yo;q`HQn`>g(};8owV~iOxo6 zk3I8`yv671f4LBl2zP1WeazPf%-0Y1r(?-iUJ-xPaN*5T{XQS8G*+ z)>|BU73HQnY{Jxg-PDVZ51s$>g zsTl?>1`ZqF6Zht_>u%ThEWDgJKsD+5{g-0NS6>wmry89t^L=V?UgOVfFRtd%7NcR~ zyk7fIld|+meA2xcBs$u#xuh`UD8!z{oS^N0OnAxcLpi|tUdp&CJ zw6MqRbbLEsjcdve@^Kx(pcBx7TS&t_#2{aG@cOynR@CFUaMv7kC*59_cP|%0n7bBy zPj2?zUC2S02qITVuaE5^P7=HatvN2;5gF#A2jM%sln6#PPvQZ-t~TGb`BE>mt}`cN zonPp!J6Z(XH4Wwt=VqHa3vTTV5$RYlH}}y_mF}m}tx|9JZOi_VRGMA`_dmhRP=?^|200JNY0w4eaAOHd&00JNY0;h_=qsXL?&BkZruh!3J%%+TzW)m%7xe&`F${va;4@;^+6>Z+_}a{~@NC4UOu5Crt> zg%ZRFr9;InhvI51GRtDN=alTXDEzL)oFcOqHGNU@iC+-UGqw7|lokMeFrVrQMw(ic zX`h%X1aw#PHJ1`yTB_A*ixjCcIIu`D)Rr2XOFGk)?DgETrY~#xd|qE!F*1xTGdjlf zjH12SjBxfwxtw~$=l^2j*8=_E0|Fob0w4eaAOHd&00JNY0w4eaAaDW%isJZ{E8g7s z=6rp@qqh~j%Qm#C#JkrM@c;j(M6sv_2!H?xfB*=900@8p2!H?xfB*=LAn< ros2 launch nav2_bringup bringup_launch.py slam:=True map:=/repo/map.yaml use_sim_time:=False use_composition:=True - params_file:=/overlay_ws/src/cps_loki_bringup/config/nav2.yaml + params_file:=/repo/config/nav2_params.yaml depends_on: - lidar - controller @@ -137,9 +137,6 @@ services: ################################################################################################################################### # Webgui Supervision via Foxglove Studio # ################################################################################################################################### - - - # config: # container_name: olivetin # image: ghcr.io/bjoernellens1/cps_bot_mini_ws/olivetin @@ -233,7 +230,7 @@ services: # - RMW_IMPLEMENTATION=rmw_cyclonedds_cpp # Foxglove Studio Bridge - foxglove-bridge: + foxglove_bridge: extends: overlay command: > ros2 launch foxglove_bridge foxglove_bridge_launch.xml port:=8765 @@ -250,7 +247,7 @@ services: #image: husarion/foxglove image: ghcr.io/foxglove/studio:latest depends_on: - - foxglove-bridge + - foxglove_bridge ports: - 8080:8080 volumes: @@ -264,6 +261,29 @@ services: rviz2 # Needed to display graphical applications privileged: true + + + +################################################################################################################################ +# Core Services for Web Management # +################################################################################################################################ + + npm: # nginx proxy manager for reverse proxying the webservices + #user "bjoern.ellensohn@unileoben.ac.at" + #password "cpsloki_npm" + image: 'jc21/nginx-proxy-manager:latest' + restart: always #unless-stopped + ports: + - '80:80' + - '81:81' + - '443:443' + volumes: + - ./config/npm:/data + - ./letsencrypt:/etc/letsencrypt + +################################################################################################################################ +# Docker related extra stuff # +################################################################################################################################ networks: {} volumes: - portainer_data: + portainer_data: \ No newline at end of file diff --git a/sudo b/sudo deleted file mode 100644 index c0230c8..0000000 --- a/sudo +++ /dev/null @@ -1 +0,0 @@ -powersave tee /sys/devices/system/cpu/cpu0/cpufreq/scaling_governor /sys/devices/system/cpu/cpu1/cpufreq/scaling_governor