From 83e00c900896e1459b5352de0edf07bbeb6ae7b7 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Bj=C3=B6rn=20Ellensohn?= Date: Wed, 12 Jul 2023 10:02:11 +0200 Subject: [PATCH 01/46] update --- config/diffbot_controllers.yaml | 2 +- config/ekf.yaml | 57 +++++++++++++++++++++++++++++ launch/robot_localization.launch.py | 19 +++++++++- package.xml | 1 + 4 files changed, 77 insertions(+), 2 deletions(-) create mode 100644 config/ekf.yaml diff --git a/config/diffbot_controllers.yaml b/config/diffbot_controllers.yaml index 842acf8..132a702 100644 --- a/config/diffbot_controllers.yaml +++ b/config/diffbot_controllers.yaml @@ -35,7 +35,7 @@ diffbot_base_controller: [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0] # changed from https://github.com/kallaspriit/rosbot/blob/main/ros/src/rosbot_description/config/diff_drive_controller.yaml open_loop: false - enable_odom_tf: true + #enable_odom_tf: true #disabled because tf will be handled by robot_localizaion node in the future (imu sensor fusion) cmd_vel_timeout: 0.5 #publish_limited_velocity: true diff --git a/config/ekf.yaml b/config/ekf.yaml new file mode 100644 index 0000000..0d3e511 --- /dev/null +++ b/config/ekf.yaml @@ -0,0 +1,57 @@ +### ekf config file ### +ekf_filter_node: + ros__parameters: +# The frequency, in Hz, at which the filter will output a position estimate. Note that the filter will not begin +# computation until it receives at least one message from one of theinputs. It will then run continuously at the +# frequency specified here, regardless of whether it receives more measurements. Defaults to 30 if unspecified. + frequency: 30.0 + +# ekf_localization_node and ukf_localization_node both use a 3D omnidirectional motion model. If this parameter is +# set to true, no 3D information will be used in your state estimate. Use this if you are operating in a planar +# environment and want to ignore the effect of small variations in the ground plane that might otherwise be detected +# by, for example, an IMU. Defaults to false if unspecified. + two_d_mode: false + +# Whether to publish the acceleration state. Defaults to false if unspecified. + publish_acceleration: true + +# Whether to broadcast the transformation over the /tf topic. Defaultsto true if unspecified. + publish_tf: true + +# 1. Set the map_frame, odom_frame, and base_link frames to the appropriate frame names for your system. +# 1a. If your system does not have a map_frame, just remove it, and make sure "world_frame" is set to the value of odom_frame. +# 2. If you are fusing continuous position data such as wheel encoder odometry, visual odometry, or IMU data, set "world_frame" +# to your odom_frame value. This is the default behavior for robot_localization's state estimation nodes. +# 3. If you are fusing global absolute position data that is subject to discrete jumps (e.g., GPS or position updates from landmark +# observations) then: +# 3a. Set your "world_frame" to your map_frame value +# 3b. MAKE SURE something else is generating the odom->base_link transform. Note that this can even be another state estimation node +# from robot_localization! However, that instance should *not* fuse the global data. + map_frame: map # Defaults to "map" if unspecified + odom_frame: odom # Defaults to "odom" if unspecified + base_link_frame: base_link # Defaults to "base_link" ifunspecified + world_frame: odom # Defaults to the value ofodom_frame if unspecified + + odom0: /odom + # The order of the values of this parameter is x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. + # Configure it for x,y,z,vyaw on the odom topic + odom0_config: [true, true, true, + false, false, false, + false, false, false, + false, false, true, + false, false, false] + + + imu0: /imu/data_raw + # The order of the values of this parameter is x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. + # Configure it for ax,ay,az linear acceleration data for now. Shall not contain values already derived by each other. + # Example: Since angular velocity is fused internally to the IMU to provide the roll, pitch and yaw estimates, we should not fuse in the angular velocities used to derive that information. We also do not fuse in angular velocity due to the noisy characteristics it has when not using exceptionally high quality (and expensive) IMUs. + imu0_config: [false, false, false, + false, false, false, + false, false, false, + false, false, false, + true, true, true] + + # [ADVANCED] Some IMUs automatically remove acceleration due to gravity, and others don't. If yours doesn't, please set + # this to true, and *make sure* your data conforms to REP-103, specifically, that the data is in ENU frame. + imu0_remove_gravitational_acceleration: true \ No newline at end of file diff --git a/launch/robot_localization.launch.py b/launch/robot_localization.launch.py index 36c61eb..04d2a31 100644 --- a/launch/robot_localization.launch.py +++ b/launch/robot_localization.launch.py @@ -118,6 +118,22 @@ def generate_launch_description(): parameters=[lidar_dir], ) + robot_localization_node = Node( + package='robot_localization', + executable='ekf_node', + name='ekf_filter_node', + output='screen', + parameters = [ PathJoinSubstitution( + [ + FindPackageShare("bot_mini_bringup"), + "config", + "ekf.yaml" + ] + ) , + #{'use_sim_time': LaunchConfiguration('use_sim_time')} + ] + ) + return LaunchDescription([ #control_node, #robot_state_pub_node, @@ -127,5 +143,6 @@ def generate_launch_description(): #teleop_spawner, #cam_node, #lidar_node, - mapper_node + #mapper_node, + robot_localization_node ]) \ No newline at end of file diff --git a/package.xml b/package.xml index 11a1ae4..34cb978 100644 --- a/package.xml +++ b/package.xml @@ -21,6 +21,7 @@ ros2_cam_openCV joy twist_mux + robot_localization ament_python From c820e365ce4cf801203f78e886186aba4a0f3aa6 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Bj=C3=B6rn=20Ellensohn?= Date: Wed, 12 Jul 2023 12:00:03 +0200 Subject: [PATCH 02/46] update diffbot covariance matrix --- config/diffbot_controllers.yaml | 12 ++++++++---- config/ekf.yaml | 2 +- 2 files changed, 9 insertions(+), 5 deletions(-) diff --git a/config/diffbot_controllers.yaml b/config/diffbot_controllers.yaml index 132a702..17f680d 100644 --- a/config/diffbot_controllers.yaml +++ b/config/diffbot_controllers.yaml @@ -29,11 +29,15 @@ diffbot_base_controller: base_frame_id: base_link # pose_covariance_diagonal : [0.001, 0.001, 0.001, 0.001, 0.001, 0.01] # twist_covariance_diagonal: [0.001, 0.001, 0.001, 0.001, 0.001, 0.01] - pose_covariance_diagonal: - [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0] - twist_covariance_diagonal: - [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0] # changed from https://github.com/kallaspriit/rosbot/blob/main/ros/src/rosbot_description/config/diff_drive_controller.yaml + # pose_covariance_diagonal: + # [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0] + # twist_covariance_diagonal: + # [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0] # changed from https://github.com/kallaspriit/rosbot/blob/main/ros/src/rosbot_description/config/diff_drive_controller.yaml + # Updated covariance matrix to small values on the diagonal axis for package ros_localization. This is recommended for diffdrive rorbots. + pose_covariance_diagonal : [0.0001, 0.0001, 0.0001, 0.0001, 0.0001, 0.0001] + twist_covariance_diagonal: [0.0001, 0.0001, 0.0001, 0.0001, 0.0001, 0.0001] + open_loop: false #enable_odom_tf: true #disabled because tf will be handled by robot_localizaion node in the future (imu sensor fusion) diff --git a/config/ekf.yaml b/config/ekf.yaml index 0d3e511..3bdce99 100644 --- a/config/ekf.yaml +++ b/config/ekf.yaml @@ -54,4 +54,4 @@ ekf_filter_node: # [ADVANCED] Some IMUs automatically remove acceleration due to gravity, and others don't. If yours doesn't, please set # this to true, and *make sure* your data conforms to REP-103, specifically, that the data is in ENU frame. - imu0_remove_gravitational_acceleration: true \ No newline at end of file + imu0_remove_gravitational_acceleration: false \ No newline at end of file From 485e48a755ba043edafb865969a2189f8f78d8e7 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Bj=C3=B6rn=20Ellensohn?= Date: Fri, 14 Jul 2023 08:48:51 +0200 Subject: [PATCH 03/46] update --- config/ekf.yaml | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/config/ekf.yaml b/config/ekf.yaml index 3bdce99..195a07f 100644 --- a/config/ekf.yaml +++ b/config/ekf.yaml @@ -10,13 +10,13 @@ ekf_filter_node: # set to true, no 3D information will be used in your state estimate. Use this if you are operating in a planar # environment and want to ignore the effect of small variations in the ground plane that might otherwise be detected # by, for example, an IMU. Defaults to false if unspecified. - two_d_mode: false + two_d_mode: true # Whether to publish the acceleration state. Defaults to false if unspecified. publish_acceleration: true # Whether to broadcast the transformation over the /tf topic. Defaultsto true if unspecified. - publish_tf: true + publish_tf: true #was true # 1. Set the map_frame, odom_frame, and base_link frames to the appropriate frame names for your system. # 1a. If your system does not have a map_frame, just remove it, and make sure "world_frame" is set to the value of odom_frame. @@ -35,10 +35,10 @@ ekf_filter_node: odom0: /odom # The order of the values of this parameter is x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. # Configure it for x,y,z,vyaw on the odom topic - odom0_config: [true, true, true, - false, false, false, - false, false, false, + odom0_config: [true , true , true, false, false, true, + false, false, false, + false, false, false, false, false, false] @@ -49,9 +49,9 @@ ekf_filter_node: imu0_config: [false, false, false, false, false, false, false, false, false, - false, false, false, - true, true, true] + false, false, true, + false, false, false] # [ADVANCED] Some IMUs automatically remove acceleration due to gravity, and others don't. If yours doesn't, please set # this to true, and *make sure* your data conforms to REP-103, specifically, that the data is in ENU frame. - imu0_remove_gravitational_acceleration: false \ No newline at end of file + imu0_remove_gravitational_acceleration: true \ No newline at end of file From 1a2de49ab630030e3ba646f638bf11f627c56ca1 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Bj=C3=B6rn=20Ellensohn?= Date: Fri, 14 Jul 2023 08:52:29 +0200 Subject: [PATCH 04/46] update --- config/ekf.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/config/ekf.yaml b/config/ekf.yaml index 195a07f..eaeb3e1 100644 --- a/config/ekf.yaml +++ b/config/ekf.yaml @@ -38,7 +38,7 @@ ekf_filter_node: odom0_config: [true , true , true, false, false, true, false, false, false, - false, false, false, + false, false, true, false, false, false] From 7c5e336efad714ca3ea88921bc2a78b43abd4bc4 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Bj=C3=B6rn=20Ellensohn?= Date: Wed, 26 Jul 2023 10:39:34 +0200 Subject: [PATCH 05/46] update --- config/diffbot_controllers.yaml | 2 +- launch/robot_controller.launch.py | 34 +---------------- launch/rsp.launch.py | 62 +------------------------------ 3 files changed, 4 insertions(+), 94 deletions(-) diff --git a/config/diffbot_controllers.yaml b/config/diffbot_controllers.yaml index 17f680d..eba6cc9 100644 --- a/config/diffbot_controllers.yaml +++ b/config/diffbot_controllers.yaml @@ -41,7 +41,7 @@ diffbot_base_controller: open_loop: false #enable_odom_tf: true #disabled because tf will be handled by robot_localizaion node in the future (imu sensor fusion) - cmd_vel_timeout: 0.5 + cmd_vel_timeout: 0.1 #publish_limited_velocity: true use_stamped_vel: false velocity_rolling_window_size: 10 # changed from https://github.com/kallaspriit/rosbot/blob/main/ros/src/rosbot_description/config/diff_drive_controller.yaml diff --git a/launch/robot_controller.launch.py b/launch/robot_controller.launch.py index 3dbdbb3..a38dec4 100644 --- a/launch/robot_controller.launch.py +++ b/launch/robot_controller.launch.py @@ -72,39 +72,9 @@ def generate_launch_description(): arguments=["diffbot_base_controller", "-c", "/controller_manager"], ) - joystick_spawner = Node( - package="joy", - executable="joy_node" - ) - - teleop_spawner = Node( - package="rmp220_teleop", - executable="rmp220_teleop" - ) - - cam_node = Node( - package="ros2_cam_openCV", - executable="cam_node" - ) - - lidar_dir = os.path.join(get_package_share_directory('lslidar_driver'), 'params', 'lsx10.yaml') - lidar_node = LifecycleNode( - package='lslidar_driver', - executable='lslidar_driver_node', - name='lslidar_driver_node', - output='screen', - emulate_tty=True, - namespace='', - parameters=[lidar_dir], - ) - return LaunchDescription([ control_node, robot_state_pub_node, - joint_state_broadcaster_spawner, #commented out because not needed? - robot_controller_spawner, - #joystick_spawner, - #teleop_spawner, - #cam_node, - #lidar_node + joint_state_broadcaster_spawner, + robot_controller_spawner ]) \ No newline at end of file diff --git a/launch/rsp.launch.py b/launch/rsp.launch.py index 4dbe3a5..172569f 100644 --- a/launch/rsp.launch.py +++ b/launch/rsp.launch.py @@ -38,21 +38,6 @@ def generate_launch_description(): ) robot_description = {"robot_description": ParameterValue(robot_description_content, value_type=str)} - robot_controllers = PathJoinSubstitution( - [ - FindPackageShare("bot_mini_bringup"), - "config", - "diffbot_controllers.yaml", - ] - ) - - control_node = Node( - package="controller_manager", - executable="ros2_control_node", - parameters=[robot_description, robot_controllers], - output="both", - ) - robot_state_pub_node = Node( package="robot_state_publisher", executable="robot_state_publisher", @@ -60,51 +45,6 @@ def generate_launch_description(): parameters=[robot_description], ) - joint_state_broadcaster_spawner = Node( - package="controller_manager", - executable="spawner", - arguments=["joint_state_broadcaster", "-c", "/controller_manager"], - ) - - robot_controller_spawner = Node( - package="controller_manager", - executable="spawner", - arguments=["diffbot_base_controller", "-c", "/controller_manager"], - ) - - joystick_spawner = Node( - package="joy", - executable="joy_node" - ) - - teleop_spawner = Node( - package="rmp220_teleop", - executable="rmp220_teleop" - ) - - cam_node = Node( - package="ros2_cam_openCV", - executable="cam_node" - ) - - lidar_dir = os.path.join(get_package_share_directory('lslidar_driver'), 'params', 'lsx10.yaml') - lidar_node = LifecycleNode( - package='lslidar_driver', - executable='lslidar_driver_node', - name='lslidar_driver_node', - output='screen', - emulate_tty=True, - namespace='', - parameters=[lidar_dir], - ) - return LaunchDescription([ - #control_node, - robot_state_pub_node, - #joint_state_broadcaster_spawner, - #robot_controller_spawner, - #joystick_spawner, - #teleop_spawner, - #cam_node, - #lidar_node + robot_state_pub_node ]) \ No newline at end of file From e3c8b41951084a261a74ba2df6c87d2eaf8aa001 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Bj=C3=B6rn=20Ellensohn?= Date: Wed, 26 Jul 2023 10:44:45 +0200 Subject: [PATCH 06/46] update --- package.xml | 1 - 1 file changed, 1 deletion(-) diff --git a/package.xml b/package.xml index 34cb978..0de9fbd 100644 --- a/package.xml +++ b/package.xml @@ -18,7 +18,6 @@ navigation2 ros2_control ros2_controllers - ros2_cam_openCV joy twist_mux robot_localization From 3b12f4e289e148b73482cf708e504b4387e4dc5f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Bj=C3=B6rn=20Ellensohn?= Date: Wed, 26 Jul 2023 12:29:09 +0200 Subject: [PATCH 07/46] update: nav2 odometry filtered --- config/nav2_params.yaml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/config/nav2_params.yaml b/config/nav2_params.yaml index 14fe6e4..81aed33 100644 --- a/config/nav2_params.yaml +++ b/config/nav2_params.yaml @@ -44,7 +44,7 @@ bt_navigator: use_sim_time: True global_frame: map robot_base_frame: base_link - odom_topic: /odom + 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: @@ -342,7 +342,7 @@ velocity_smoother: 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: "odom" + odom_topic: "/odometry/filtered" odom_duration: 0.1 deadband_velocity: [0.0, 0.0, 0.0] velocity_timeout: 1.0 \ No newline at end of file From a82781dbf088acd032357cfd2a602f407b3d9bba Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Bj=C3=B6rn=20Ellensohn?= Date: Wed, 26 Jul 2023 12:32:51 +0200 Subject: [PATCH 08/46] update: ekf params --- config/ekf.yaml | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/config/ekf.yaml b/config/ekf.yaml index eaeb3e1..c88dbb6 100644 --- a/config/ekf.yaml +++ b/config/ekf.yaml @@ -35,12 +35,13 @@ ekf_filter_node: odom0: /odom # The order of the values of this parameter is x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. # Configure it for x,y,z,vyaw on the odom topic - odom0_config: [true , true , true, + odom0_config: [true , true , false, false, false, true, false, false, false, false, false, true, false, false, false] - + odom0_differential: true + odom0_relative: true imu0: /imu/data_raw # The order of the values of this parameter is x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. @@ -51,6 +52,8 @@ ekf_filter_node: false, false, false, false, false, true, false, false, false] + imu0_differential: true + imu0_relative: true # [ADVANCED] Some IMUs automatically remove acceleration due to gravity, and others don't. If yours doesn't, please set # this to true, and *make sure* your data conforms to REP-103, specifically, that the data is in ENU frame. From 985faa70cb4da587c503e32a0eb0083413e8df5e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Bj=C3=B6rn=20Ellensohn?= Date: Wed, 26 Jul 2023 12:33:52 +0200 Subject: [PATCH 09/46] controller re enabled odom tf --- config/diffbot_controllers.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/config/diffbot_controllers.yaml b/config/diffbot_controllers.yaml index eba6cc9..8692610 100644 --- a/config/diffbot_controllers.yaml +++ b/config/diffbot_controllers.yaml @@ -39,7 +39,7 @@ diffbot_base_controller: twist_covariance_diagonal: [0.0001, 0.0001, 0.0001, 0.0001, 0.0001, 0.0001] open_loop: false - #enable_odom_tf: true #disabled because tf will be handled by robot_localizaion node in the future (imu sensor fusion) + enable_odom_tf: true #disabled because tf will be handled by robot_localizaion node in the future (imu sensor fusion) cmd_vel_timeout: 0.1 #publish_limited_velocity: true From 2ead61ae93b9a69af728c72394112d7338ab4358 Mon Sep 17 00:00:00 2001 From: bjoernellens1 <64093272+bjoernellens1@users.noreply.github.com> Date: Mon, 16 Oct 2023 16:18:52 +0200 Subject: [PATCH 10/46] Update robot_joy_teleop.launch.py --- launch/robot_joy_teleop.launch.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/launch/robot_joy_teleop.launch.py b/launch/robot_joy_teleop.launch.py index 747444b..b409ddd 100644 --- a/launch/robot_joy_teleop.launch.py +++ b/launch/robot_joy_teleop.launch.py @@ -80,7 +80,7 @@ def generate_launch_description(): teleop_spawner = Node( package="rmp220_teleop", executable="rmp220_teleop", - remappings=[('/diffbot_base_controller/cmd_vel_unstamped','/cmd_vel_joy')] + remappings=[('/cmd_vel','/diffbot_base_controller/cmd_vel_unstamped')] ) cam_node = Node( @@ -117,4 +117,4 @@ def generate_launch_description(): #cam_node, #lidar_node, #twist_mux - ]) \ No newline at end of file + ]) From 7b83d4e357ca1739852cf8c974c26154e5efaecf Mon Sep 17 00:00:00 2001 From: bjoernellens1 <64093272+bjoernellens1@users.noreply.github.com> Date: Thu, 16 Nov 2023 11:17:16 +0100 Subject: [PATCH 11/46] Update robot_joy_teleop.launch.py --- launch/robot_joy_teleop.launch.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/launch/robot_joy_teleop.launch.py b/launch/robot_joy_teleop.launch.py index b409ddd..19d564b 100644 --- a/launch/robot_joy_teleop.launch.py +++ b/launch/robot_joy_teleop.launch.py @@ -104,7 +104,7 @@ def generate_launch_description(): package="twist_mux", executable="twist_mux", parameters=[twist_mux_params, {'use_sim_time': False}], - remappings=[('/cmd_vel_out','/diffbot_base_controller/cmd_vel_unstamped')] + remappings=[('/cmd_vel_out','/cmd_vel_mux')] ) return LaunchDescription([ From dd8c00709942272c6a50daac2518ad2581e143aa Mon Sep 17 00:00:00 2001 From: bjoernellens1 <64093272+bjoernellens1@users.noreply.github.com> Date: Thu, 16 Nov 2023 11:18:00 +0100 Subject: [PATCH 12/46] Update robot_joy_teleop.launch.py --- launch/robot_joy_teleop.launch.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/launch/robot_joy_teleop.launch.py b/launch/robot_joy_teleop.launch.py index 19d564b..55806ef 100644 --- a/launch/robot_joy_teleop.launch.py +++ b/launch/robot_joy_teleop.launch.py @@ -116,5 +116,5 @@ def generate_launch_description(): teleop_spawner, #cam_node, #lidar_node, - #twist_mux + twist_mux ]) From 166628020c286ff625cd6d029b4453b9acb27049 Mon Sep 17 00:00:00 2001 From: bjoernellens1 <64093272+bjoernellens1@users.noreply.github.com> Date: Thu, 16 Nov 2023 11:25:45 +0100 Subject: [PATCH 13/46] Update robot_joy_teleop.launch.py --- launch/robot_joy_teleop.launch.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/launch/robot_joy_teleop.launch.py b/launch/robot_joy_teleop.launch.py index 55806ef..e3cd875 100644 --- a/launch/robot_joy_teleop.launch.py +++ b/launch/robot_joy_teleop.launch.py @@ -80,7 +80,7 @@ def generate_launch_description(): teleop_spawner = Node( package="rmp220_teleop", executable="rmp220_teleop", - remappings=[('/cmd_vel','/diffbot_base_controller/cmd_vel_unstamped')] + remappings=[('cmd_vel', 'cmd_vel_joy')], ) cam_node = Node( From 757fe7e4ecf4c92fce1181f77246799ab88d0432 Mon Sep 17 00:00:00 2001 From: bjoernellens1 <64093272+bjoernellens1@users.noreply.github.com> Date: Thu, 16 Nov 2023 11:26:44 +0100 Subject: [PATCH 14/46] Update twist_mux.yaml --- config/twist_mux.yaml | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/config/twist_mux.yaml b/config/twist_mux.yaml index 375a961..e3333b0 100644 --- a/config/twist_mux.yaml +++ b/config/twist_mux.yaml @@ -1,6 +1,10 @@ twist_mux: ros__parameters: topics: + common: + topic : cmd_vel_common + timeout : 0.5 + priority: 0 navigation: topic : cmd_vel timeout : 0.5 @@ -12,4 +16,4 @@ twist_mux: joystick: topic : cmd_vel_joy timeout : 0.5 - priority: 5 \ No newline at end of file + priority: 50 From af2b2bb27e1cc523c627eb4b2b1eab3cf4895efd Mon Sep 17 00:00:00 2001 From: bjoernellens1 <64093272+bjoernellens1@users.noreply.github.com> Date: Thu, 16 Nov 2023 11:37:24 +0100 Subject: [PATCH 15/46] Update robot_joy_teleop.launch.py --- launch/robot_joy_teleop.launch.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/launch/robot_joy_teleop.launch.py b/launch/robot_joy_teleop.launch.py index e3cd875..5684649 100644 --- a/launch/robot_joy_teleop.launch.py +++ b/launch/robot_joy_teleop.launch.py @@ -104,7 +104,7 @@ def generate_launch_description(): package="twist_mux", executable="twist_mux", parameters=[twist_mux_params, {'use_sim_time': False}], - remappings=[('/cmd_vel_out','/cmd_vel_mux')] + remappings=[('/cmd_vel_out','/diffbot_base_controller/cmd_vel_unstamped')] ) return LaunchDescription([ From 4e5ca62cfe04b9b8283c478ad8f5a89222452b0a Mon Sep 17 00:00:00 2001 From: bjoernellens1 <64093272+bjoernellens1@users.noreply.github.com> Date: Thu, 16 Nov 2023 13:34:14 +0100 Subject: [PATCH 16/46] Update nav2_params.yaml --- config/nav2_params.yaml | 78 ++++++++++++++++++++++++++++++++++++++++- 1 file changed, 77 insertions(+), 1 deletion(-) diff --git a/config/nav2_params.yaml b/config/nav2_params.yaml index 81aed33..27ec277 100644 --- a/config/nav2_params.yaml +++ b/config/nav2_params.yaml @@ -1,3 +1,79 @@ +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.05 + 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 @@ -345,4 +421,4 @@ velocity_smoother: odom_topic: "/odometry/filtered" odom_duration: 0.1 deadband_velocity: [0.0, 0.0, 0.0] - velocity_timeout: 1.0 \ No newline at end of file + velocity_timeout: 1.0 From 7cab902ab2c077e946a48dc5afa60029e6eb9520 Mon Sep 17 00:00:00 2001 From: bjoernellens1 <64093272+bjoernellens1@users.noreply.github.com> Date: Thu, 16 Nov 2023 13:46:13 +0100 Subject: [PATCH 17/46] Create joystick.yaml --- config/joystick.yaml | 28 ++++++++++++++++++++++++++++ 1 file changed, 28 insertions(+) create mode 100644 config/joystick.yaml diff --git a/config/joystick.yaml b/config/joystick.yaml new file mode 100644 index 0000000..5871b8f --- /dev/null +++ b/config/joystick.yaml @@ -0,0 +1,28 @@ +joy_node: + ros__parameters: + device_id: 0 + deadzone: 0.05 + autorepeat_rate: 0.00 + coalesce_interval: 0.001 # merging messeges in this interval + +teleop_node: + ros__parameters: + axis_linear: + x: 1 + scale_linear: + x: 0.7 + scale_linear_turbo: + x: 1.5 + + axis_angular: + yaw: 0 + scale_angular: + yaw: 1.4 + scale_angular_turbo: + yaw: 3.0 + + + enable_button: 2 + enable_turbo_button: 5 + + require_enable_button: false From f0225e21af81b2204933151a304c2d5a4abac884 Mon Sep 17 00:00:00 2001 From: bjoernellens1 <64093272+bjoernellens1@users.noreply.github.com> Date: Thu, 16 Nov 2023 13:50:04 +0100 Subject: [PATCH 18/46] Update robot_joy_teleop.launch.py --- launch/robot_joy_teleop.launch.py | 24 +++++++++++++++++++++--- 1 file changed, 21 insertions(+), 3 deletions(-) diff --git a/launch/robot_joy_teleop.launch.py b/launch/robot_joy_teleop.launch.py index 5684649..0ec0a3a 100644 --- a/launch/robot_joy_teleop.launch.py +++ b/launch/robot_joy_teleop.launch.py @@ -107,14 +107,32 @@ def generate_launch_description(): remappings=[('/cmd_vel_out','/diffbot_base_controller/cmd_vel_unstamped')] ) + joy_node = Node( + package='joy', + executable='joy_node', + parameters=[joy_params, {'use_sim_time': use_sim_time}], + #namespace = namespace + ) + + teleop_node = Node( + package='teleop_twist_joy', + executable='teleop_node', + name='teleop_node', + parameters=[joy_params, {'use_sim_time': use_sim_time}], + remappings=[('cmd_vel', 'cmd_vel_joy')], + #namespace = namespace + ) + return LaunchDescription([ #control_node, #robot_state_pub_node, #joint_state_broadcaster_spawner, #robot_controller_spawner, - joystick_spawner, - teleop_spawner, + #joystick_spawner, + #teleop_spawner, #cam_node, #lidar_node, - twist_mux + twist_mux, + joy_node, + teleop_node ]) From 8eb6a862f2addb4f3153ad3df109be23939363d6 Mon Sep 17 00:00:00 2001 From: bjoernellens1 <64093272+bjoernellens1@users.noreply.github.com> Date: Thu, 16 Nov 2023 13:52:45 +0100 Subject: [PATCH 19/46] Update robot_joy_teleop.launch.py --- launch/robot_joy_teleop.launch.py | 1 + 1 file changed, 1 insertion(+) diff --git a/launch/robot_joy_teleop.launch.py b/launch/robot_joy_teleop.launch.py index 0ec0a3a..5d8b6f9 100644 --- a/launch/robot_joy_teleop.launch.py +++ b/launch/robot_joy_teleop.launch.py @@ -107,6 +107,7 @@ def generate_launch_description(): remappings=[('/cmd_vel_out','/diffbot_base_controller/cmd_vel_unstamped')] ) + joy_params = os.path.join(get_package_share_directory('bot_mini_bringup'),'config','joystick.yaml') joy_node = Node( package='joy', executable='joy_node', From 73b0fdd034586cda471c4a4be908f921785d1f39 Mon Sep 17 00:00:00 2001 From: bjoernellens1 <64093272+bjoernellens1@users.noreply.github.com> Date: Thu, 16 Nov 2023 13:54:19 +0100 Subject: [PATCH 20/46] Update robot_joy_teleop.launch.py --- launch/robot_joy_teleop.launch.py | 1 + 1 file changed, 1 insertion(+) diff --git a/launch/robot_joy_teleop.launch.py b/launch/robot_joy_teleop.launch.py index 5d8b6f9..aebba47 100644 --- a/launch/robot_joy_teleop.launch.py +++ b/launch/robot_joy_teleop.launch.py @@ -107,6 +107,7 @@ def generate_launch_description(): remappings=[('/cmd_vel_out','/diffbot_base_controller/cmd_vel_unstamped')] ) + use_sim_time = false joy_params = os.path.join(get_package_share_directory('bot_mini_bringup'),'config','joystick.yaml') joy_node = Node( package='joy', From e441c1aab7b15c85741ed7ea40cd1432842fec0d Mon Sep 17 00:00:00 2001 From: bjoernellens1 <64093272+bjoernellens1@users.noreply.github.com> Date: Thu, 16 Nov 2023 13:56:18 +0100 Subject: [PATCH 21/46] Update robot_joy_teleop.launch.py --- launch/robot_joy_teleop.launch.py | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/launch/robot_joy_teleop.launch.py b/launch/robot_joy_teleop.launch.py index aebba47..e2692e0 100644 --- a/launch/robot_joy_teleop.launch.py +++ b/launch/robot_joy_teleop.launch.py @@ -14,7 +14,7 @@ import os from launch import LaunchDescription -from launch.substitutions import Command, FindExecutable, PathJoinSubstitution +from launch.substitutions import Command, FindExecutable, PathJoinSubstitution, LaunchConfiguration from launch_ros.actions import Node from launch_ros.substitutions import FindPackageShare from ament_index_python.packages import get_package_share_directory @@ -23,6 +23,8 @@ from launch_ros.descriptions import ParameterValue def generate_launch_description(): + use_sim_time = LaunchConfiguration('use_sim_time') + robot_description_content = Command( [ PathJoinSubstitution([FindExecutable(name="xacro")]), @@ -107,7 +109,6 @@ def generate_launch_description(): remappings=[('/cmd_vel_out','/diffbot_base_controller/cmd_vel_unstamped')] ) - use_sim_time = false joy_params = os.path.join(get_package_share_directory('bot_mini_bringup'),'config','joystick.yaml') joy_node = Node( package='joy', From 2f1bb62abb572b11f43f2d43cd341b5bfe1e3421 Mon Sep 17 00:00:00 2001 From: bjoernellens1 <64093272+bjoernellens1@users.noreply.github.com> Date: Thu, 16 Nov 2023 13:57:29 +0100 Subject: [PATCH 22/46] Update robot_joy_teleop.launch.py --- launch/robot_joy_teleop.launch.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/launch/robot_joy_teleop.launch.py b/launch/robot_joy_teleop.launch.py index e2692e0..a4f296f 100644 --- a/launch/robot_joy_teleop.launch.py +++ b/launch/robot_joy_teleop.launch.py @@ -23,7 +23,8 @@ from launch_ros.descriptions import ParameterValue def generate_launch_description(): - use_sim_time = LaunchConfiguration('use_sim_time') + #use_sim_time = LaunchConfiguration('use_sim_time') + use_sim_time = True robot_description_content = Command( [ From 1f12768a53c8d3ae9c714b4cd00093d5a6d7587c Mon Sep 17 00:00:00 2001 From: bjoernellens1 <64093272+bjoernellens1@users.noreply.github.com> Date: Thu, 16 Nov 2023 14:05:33 +0100 Subject: [PATCH 23/46] Update joystick.yaml --- config/joystick.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/config/joystick.yaml b/config/joystick.yaml index 5871b8f..819543c 100644 --- a/config/joystick.yaml +++ b/config/joystick.yaml @@ -3,7 +3,7 @@ joy_node: device_id: 0 deadzone: 0.05 autorepeat_rate: 0.00 - coalesce_interval: 0.001 # merging messeges in this interval + #coalesce_interval: 0.001 # merging messeges in this interval teleop_node: ros__parameters: From 6c99f3f6db0b95179601c77663a9c34bfba133ef Mon Sep 17 00:00:00 2001 From: bjoernellens1 <64093272+bjoernellens1@users.noreply.github.com> Date: Thu, 16 Nov 2023 14:06:34 +0100 Subject: [PATCH 24/46] Update joystick.yaml --- config/joystick.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/config/joystick.yaml b/config/joystick.yaml index 819543c..4558770 100644 --- a/config/joystick.yaml +++ b/config/joystick.yaml @@ -2,7 +2,7 @@ joy_node: ros__parameters: device_id: 0 deadzone: 0.05 - autorepeat_rate: 0.00 + autorepeat_rate: 5.00 #coalesce_interval: 0.001 # merging messeges in this interval teleop_node: From bf049490c34a6626859fbd5deb9dd7f0acca8b4a Mon Sep 17 00:00:00 2001 From: bjoernellens1 <64093272+bjoernellens1@users.noreply.github.com> Date: Thu, 16 Nov 2023 14:21:31 +0100 Subject: [PATCH 25/46] Update nav2_params.yaml --- config/nav2_params.yaml | 732 +++++++++++++++++++++++++++++++++------- 1 file changed, 615 insertions(+), 117 deletions(-) diff --git a/config/nav2_params.yaml b/config/nav2_params.yaml index 27ec277..41023d1 100644 --- a/config/nav2_params.yaml +++ b/config/nav2_params.yaml @@ -1,3 +1,430 @@ +# 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.05 +# 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: 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 + +# 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 + +# 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.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 + +# 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 +# plugins: ["voxel_layer", "inflation_layer"] +# inflation_layer: +# plugin: "nav2_costmap_2d::InflationLayer" +# cost_scaling_factor: 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: scan +# scan: +# topic: /scan +# 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 +# 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 +# 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 +# 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: 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 + +# 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: "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 +# deadband_velocity: [0.0, 0.0, 0.0] +# velocity_timeout: 1.0 + + + slam_toolbox: ros__parameters: @@ -90,7 +517,7 @@ amcl: global_frame_id: "map" lambda_short: 0.1 laser_likelihood_max_dist: 2.0 - laser_max_range: 100.0 + laser_max_range: 7.0 #was 100.0 laser_min_range: -1.0 laser_model_type: "likelihood_field" max_beams: 60 @@ -120,7 +547,7 @@ bt_navigator: use_sim_time: True global_frame: map robot_base_frame: base_link - odom_topic: /odometry/filtered + odom_topic: /odom bt_loop_duration: 10 default_server_timeout: 20 # 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults: @@ -128,52 +555,53 @@ bt_navigator: # 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_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: @@ -183,76 +611,123 @@ 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: 20.0 + 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 - failure_tolerance: 0.3 - progress_checker_plugin: "progress_checker" - goal_checker_plugins: ["general_goal_checker"] # "precise_goal_checker" + progress_checker_plugins: ["progress_checker"] # progress_checker_plugin: "progress_checker" For Humble and older + goal_checker_plugins: ["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 + goal_checker: 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 + xy_goal_tolerance: 0.25 # was 0.25 + yaw_goal_tolerance: 0.25 # was 0.25 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 + 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: @@ -266,11 +741,12 @@ local_costmap: width: 3 height: 3 resolution: 0.05 - robot_radius: 0.22 + #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: 3.0 + cost_scaling_factor: 10.0 # was 3.0 inflation_radius: 0.55 voxel_layer: plugin: "nav2_costmap_2d::VoxelLayer" @@ -305,7 +781,8 @@ global_costmap: global_frame: map robot_base_frame: base_link use_sim_time: True - robot_radius: 0.22 + #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"] @@ -328,7 +805,7 @@ global_costmap: map_subscribe_transient_local: True inflation_layer: plugin: "nav2_costmap_2d::InflationLayer" - cost_scaling_factor: 3.0 + cost_scaling_factor: 10.0 # was 3.0 inflation_radius: 0.55 always_send_full_costmap: True @@ -347,16 +824,37 @@ map_saver: 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: - expected_planner_frequency: 20.0 - use_sim_time: True planner_plugins: ["GridBased"] + use_sim_time: True + GridBased: - plugin: "nav2_navfn_planner/NavfnPlanner" - tolerance: 0.5 - use_astar: false - allow_unknown: true + 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: @@ -413,12 +911,12 @@ velocity_smoother: use_sim_time: True smoothing_frequency: 20.0 scale_velocities: False - feedback: "OPEN_LOOP" + feedback: "OPEN_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 + odom_topic: "/odom + odom_duration: 0.1 # was 0.1 deadband_velocity: [0.0, 0.0, 0.0] velocity_timeout: 1.0 From e4fcb7b08176e00904c9681404ac6d1f75e0d901 Mon Sep 17 00:00:00 2001 From: bjoernellens1 <64093272+bjoernellens1@users.noreply.github.com> Date: Thu, 16 Nov 2023 14:23:03 +0100 Subject: [PATCH 26/46] Update diffbot_controllers.yaml --- config/diffbot_controllers.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/config/diffbot_controllers.yaml b/config/diffbot_controllers.yaml index 8692610..d4b4ce2 100644 --- a/config/diffbot_controllers.yaml +++ b/config/diffbot_controllers.yaml @@ -41,7 +41,7 @@ diffbot_base_controller: open_loop: false enable_odom_tf: true #disabled because tf will be handled by robot_localizaion node in the future (imu sensor fusion) - cmd_vel_timeout: 0.1 + cmd_vel_timeout: 0.5 # was 0.1 #publish_limited_velocity: true use_stamped_vel: false velocity_rolling_window_size: 10 # changed from https://github.com/kallaspriit/rosbot/blob/main/ros/src/rosbot_description/config/diff_drive_controller.yaml From 6219db5d55d21e53f16a71f4ab958ecf635d083f Mon Sep 17 00:00:00 2001 From: bjoernellens1 <64093272+bjoernellens1@users.noreply.github.com> Date: Thu, 16 Nov 2023 14:23:54 +0100 Subject: [PATCH 27/46] Update nav2_params.yaml --- config/nav2_params.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/config/nav2_params.yaml b/config/nav2_params.yaml index 41023d1..cca2037 100644 --- a/config/nav2_params.yaml +++ b/config/nav2_params.yaml @@ -916,7 +916,7 @@ velocity_smoother: 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: "/odom + odom_topic: "/odom" odom_duration: 0.1 # was 0.1 deadband_velocity: [0.0, 0.0, 0.0] velocity_timeout: 1.0 From 07a533e2081e23ab0dbf6bde6b66f503759a9afe Mon Sep 17 00:00:00 2001 From: bjoernellens1 <64093272+bjoernellens1@users.noreply.github.com> Date: Thu, 16 Nov 2023 14:29:31 +0100 Subject: [PATCH 28/46] Update diffbot_controllers.yaml --- config/diffbot_controllers.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/config/diffbot_controllers.yaml b/config/diffbot_controllers.yaml index d4b4ce2..6403968 100644 --- a/config/diffbot_controllers.yaml +++ b/config/diffbot_controllers.yaml @@ -41,7 +41,7 @@ diffbot_base_controller: open_loop: false enable_odom_tf: true #disabled because tf will be handled by robot_localizaion node in the future (imu sensor fusion) - cmd_vel_timeout: 0.5 # was 0.1 + cmd_vel_timeout: 1.0 # was 0.1 #publish_limited_velocity: true use_stamped_vel: false velocity_rolling_window_size: 10 # changed from https://github.com/kallaspriit/rosbot/blob/main/ros/src/rosbot_description/config/diff_drive_controller.yaml From 67520d12ce94c672a69b9754cf9b379a3af51acd Mon Sep 17 00:00:00 2001 From: bjoernellens1 <64093272+bjoernellens1@users.noreply.github.com> Date: Thu, 16 Nov 2023 14:30:12 +0100 Subject: [PATCH 29/46] update --- config/joystick.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/config/joystick.yaml b/config/joystick.yaml index 4558770..819543c 100644 --- a/config/joystick.yaml +++ b/config/joystick.yaml @@ -2,7 +2,7 @@ joy_node: ros__parameters: device_id: 0 deadzone: 0.05 - autorepeat_rate: 5.00 + autorepeat_rate: 0.00 #coalesce_interval: 0.001 # merging messeges in this interval teleop_node: From 2d4e6cee51179a7dae16cacc9e4ef6e936e96936 Mon Sep 17 00:00:00 2001 From: bjoernellens1 <64093272+bjoernellens1@users.noreply.github.com> Date: Thu, 16 Nov 2023 14:37:07 +0100 Subject: [PATCH 30/46] update --- config/diffbot_controllers.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/config/diffbot_controllers.yaml b/config/diffbot_controllers.yaml index 6403968..e667752 100644 --- a/config/diffbot_controllers.yaml +++ b/config/diffbot_controllers.yaml @@ -41,7 +41,7 @@ diffbot_base_controller: open_loop: false enable_odom_tf: true #disabled because tf will be handled by robot_localizaion node in the future (imu sensor fusion) - cmd_vel_timeout: 1.0 # was 0.1 + cmd_vel_timeout: 10.0 # was 0.1 #publish_limited_velocity: true use_stamped_vel: false velocity_rolling_window_size: 10 # changed from https://github.com/kallaspriit/rosbot/blob/main/ros/src/rosbot_description/config/diff_drive_controller.yaml From 357a07657d5641ccbcc2564d70c85878af3ecb6c Mon Sep 17 00:00:00 2001 From: bjoernellens1 <64093272+bjoernellens1@users.noreply.github.com> Date: Mon, 20 Nov 2023 08:42:45 +0100 Subject: [PATCH 31/46] Update README.md --- README.md | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index a03106d..6316751 100644 --- a/README.md +++ b/README.md @@ -1 +1,3 @@ -# bot_mini_bringup +cps_loki_bringup + +This repo houses ROS2 bringup package for CPS Loki robot (small green one). From 04dc610b6e1ad71437a2881a0c37e92eb5560cd8 Mon Sep 17 00:00:00 2001 From: bjoernellens1 <64093272+bjoernellens1@users.noreply.github.com> Date: Mon, 20 Nov 2023 08:43:35 +0100 Subject: [PATCH 32/46] Update package.xml --- package.xml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/package.xml b/package.xml index 0de9fbd..ec2f079 100644 --- a/package.xml +++ b/package.xml @@ -1,9 +1,9 @@ - bot_mini_bringup - 0.0.0 - TODO: Package description + cps_loki_bringup + 0.0.2 + ROS2 bringup sources for CPS Loki Robot bjorn TODO: License declaration From 82eb6f8ffeff337953dbd91d468f3773da53b06e Mon Sep 17 00:00:00 2001 From: bjoernellens1 <64093272+bjoernellens1@users.noreply.github.com> Date: Mon, 20 Nov 2023 08:43:48 +0100 Subject: [PATCH 33/46] Update setup.cfg --- setup.cfg | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/setup.cfg b/setup.cfg index c10ffd0..bdd18b5 100644 --- a/setup.cfg +++ b/setup.cfg @@ -1,4 +1,4 @@ [develop] -script_dir=$base/lib/bot_mini_bringup +script_dir=$base/lib/cps_loki_bringup [install] -install_scripts=$base/lib/bot_mini_bringup +install_scripts=$base/lib/cps_loki_bringup From b9f5a72868af7dd75e05ab65a42892bf1142af3f Mon Sep 17 00:00:00 2001 From: bjoernellens1 <64093272+bjoernellens1@users.noreply.github.com> Date: Mon, 20 Nov 2023 08:44:04 +0100 Subject: [PATCH 34/46] Update setup.py --- setup.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/setup.py b/setup.py index 0ce3dbe..f3c8ecc 100644 --- a/setup.py +++ b/setup.py @@ -2,7 +2,7 @@ from setuptools import setup import os from glob import glob -package_name = 'bot_mini_bringup' +package_name = 'cps_loki_bringup' setup( name=package_name, From ef82cabfdd1a5f19a6a7b530f840edc622ad0bbc Mon Sep 17 00:00:00 2001 From: bjoernellens1 <64093272+bjoernellens1@users.noreply.github.com> Date: Mon, 20 Nov 2023 08:44:41 +0100 Subject: [PATCH 35/46] update --- {bot_mini_bringup => cps_loki_bringup}/__init__.py | 0 resource/{bot_mini_bringup => cps_loki_bringup} | 0 2 files changed, 0 insertions(+), 0 deletions(-) rename {bot_mini_bringup => cps_loki_bringup}/__init__.py (100%) rename resource/{bot_mini_bringup => cps_loki_bringup} (100%) diff --git a/bot_mini_bringup/__init__.py b/cps_loki_bringup/__init__.py similarity index 100% rename from bot_mini_bringup/__init__.py rename to cps_loki_bringup/__init__.py diff --git a/resource/bot_mini_bringup b/resource/cps_loki_bringup similarity index 100% rename from resource/bot_mini_bringup rename to resource/cps_loki_bringup From 8e54dc0a6ed944faad138f7c2a0040f51dce4f49 Mon Sep 17 00:00:00 2001 From: bjoernellens1 <64093272+bjoernellens1@users.noreply.github.com> Date: Mon, 20 Nov 2023 08:55:20 +0100 Subject: [PATCH 36/46] Update package.xml --- package.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/package.xml b/package.xml index ec2f079..b4fb1a9 100644 --- a/package.xml +++ b/package.xml @@ -13,11 +13,11 @@ python3-pytest odrive_demo_description - rmp220_teleop nav2_bringup navigation2 ros2_control ros2_controllers + teleop_twist_joy joy twist_mux robot_localization From f9edce1961e47aec31f9119ca9050f924bf17acd Mon Sep 17 00:00:00 2001 From: bjoernellens1 <64093272+bjoernellens1@users.noreply.github.com> Date: Mon, 20 Nov 2023 10:49:14 +0100 Subject: [PATCH 37/46] update --- launch/full_bot_mini.launch.py | 4 ++-- launch/min_bot_mini.launch.py | 4 ++-- launch/nav2.launch.py | 2 +- launch/robot_cam.launch.py | 4 ++-- launch/robot_controller.launch.py | 4 ++-- launch/robot_joy_teleop.launch.py | 8 ++++---- launch/robot_lidar.launch.py | 4 ++-- launch/robot_localization.launch.py | 8 ++++---- launch/robot_mapper.launch.py | 6 +++--- launch/robot_navigation.launch.py | 2 +- launch/robot_twist_mux.launch.py | 6 +++--- launch/rsp.launch.py | 2 +- launch/sim.launch.py | 10 +++++----- launch/sim_bot_mini.launch.py | 4 ++-- 14 files changed, 34 insertions(+), 34 deletions(-) diff --git a/launch/full_bot_mini.launch.py b/launch/full_bot_mini.launch.py index 942cb24..5f2abcb 100644 --- a/launch/full_bot_mini.launch.py +++ b/launch/full_bot_mini.launch.py @@ -29,7 +29,7 @@ def generate_launch_description(): " ", PathJoinSubstitution( [ - FindPackageShare("bot_mini_description"), + FindPackageShare("cps_loki_description"), "urdf", "odrive_diffbot.urdf.xacro" ] @@ -40,7 +40,7 @@ def generate_launch_description(): robot_controllers = PathJoinSubstitution( [ - FindPackageShare("bot_mini_bringup"), + FindPackageShare("cps_loki_bringup"), "config", "diffbot_controllers.yaml", ] diff --git a/launch/min_bot_mini.launch.py b/launch/min_bot_mini.launch.py index e7c4d5d..4c892d8 100644 --- a/launch/min_bot_mini.launch.py +++ b/launch/min_bot_mini.launch.py @@ -29,7 +29,7 @@ def generate_launch_description(): " ", PathJoinSubstitution( [ - FindPackageShare("bot_mini_description"), + FindPackageShare("cps_loki_description"), "urdf", "odrive_diffbot.urdf.xacro" ] @@ -40,7 +40,7 @@ def generate_launch_description(): robot_controllers = PathJoinSubstitution( [ - FindPackageShare("bot_mini_bringup"), + FindPackageShare("cps_loki_bringup"), "config", "diffbot_controllers.yaml", ] diff --git a/launch/nav2.launch.py b/launch/nav2.launch.py index f016df9..3c5ca58 100644 --- a/launch/nav2.launch.py +++ b/launch/nav2.launch.py @@ -28,7 +28,7 @@ from nav2_common.launch import RewrittenYaml def generate_launch_description(): # Get the launch directory - bringup_dir = get_package_share_directory('bot_mini_bringup') + bringup_dir = get_package_share_directory('cps_loki_bringup') namespace = LaunchConfiguration('namespace') use_sim_time = LaunchConfiguration('use_sim_time') diff --git a/launch/robot_cam.launch.py b/launch/robot_cam.launch.py index f3b7a60..30ae325 100644 --- a/launch/robot_cam.launch.py +++ b/launch/robot_cam.launch.py @@ -29,7 +29,7 @@ def generate_launch_description(): " ", PathJoinSubstitution( [ - FindPackageShare("bot_mini_description"), + FindPackageShare("cps_loki_description"), "urdf", "odrive_diffbot.urdf.xacro" ] @@ -40,7 +40,7 @@ def generate_launch_description(): robot_controllers = PathJoinSubstitution( [ - FindPackageShare("bot_mini_bringup"), + FindPackageShare("cps_loki_bringup"), "config", "diffbot_controllers.yaml", ] diff --git a/launch/robot_controller.launch.py b/launch/robot_controller.launch.py index a38dec4..380a06f 100644 --- a/launch/robot_controller.launch.py +++ b/launch/robot_controller.launch.py @@ -29,7 +29,7 @@ def generate_launch_description(): " ", PathJoinSubstitution( [ - FindPackageShare("bot_mini_description"), + FindPackageShare("cps_loki_description"), "urdf", "odrive_diffbot.urdf.xacro" ] @@ -40,7 +40,7 @@ def generate_launch_description(): robot_controllers = PathJoinSubstitution( [ - FindPackageShare("bot_mini_bringup"), + FindPackageShare("cps_loki_bringup"), "config", "diffbot_controllers.yaml", ] diff --git a/launch/robot_joy_teleop.launch.py b/launch/robot_joy_teleop.launch.py index a4f296f..794a3ac 100644 --- a/launch/robot_joy_teleop.launch.py +++ b/launch/robot_joy_teleop.launch.py @@ -32,7 +32,7 @@ def generate_launch_description(): " ", PathJoinSubstitution( [ - FindPackageShare("bot_mini_description"), + FindPackageShare("cps_loki_description"), "urdf", "odrive_diffbot.urdf.xacro" ] @@ -43,7 +43,7 @@ def generate_launch_description(): robot_controllers = PathJoinSubstitution( [ - FindPackageShare("bot_mini_bringup"), + FindPackageShare("cps_loki_bringup"), "config", "diffbot_controllers.yaml", ] @@ -102,7 +102,7 @@ def generate_launch_description(): parameters=[lidar_dir], ) - twist_mux_params = os.path.join(get_package_share_directory('bot_mini_bringup'),'config','twist_mux.yaml') + twist_mux_params = os.path.join(get_package_share_directory('cps_loki_bringup'),'config','twist_mux.yaml') twist_mux = Node( package="twist_mux", executable="twist_mux", @@ -110,7 +110,7 @@ def generate_launch_description(): remappings=[('/cmd_vel_out','/diffbot_base_controller/cmd_vel_unstamped')] ) - joy_params = os.path.join(get_package_share_directory('bot_mini_bringup'),'config','joystick.yaml') + joy_params = os.path.join(get_package_share_directory('cps_loki_bringup'),'config','joystick.yaml') joy_node = Node( package='joy', executable='joy_node', diff --git a/launch/robot_lidar.launch.py b/launch/robot_lidar.launch.py index d64648c..cf4af81 100644 --- a/launch/robot_lidar.launch.py +++ b/launch/robot_lidar.launch.py @@ -29,7 +29,7 @@ def generate_launch_description(): " ", PathJoinSubstitution( [ - FindPackageShare("bot_mini_description"), + FindPackageShare("cps_loki_description"), "urdf", "odrive_diffbot.urdf.xacro" ] @@ -40,7 +40,7 @@ def generate_launch_description(): robot_controllers = PathJoinSubstitution( [ - FindPackageShare("bot_mini_bringup"), + FindPackageShare("cps_loki_bringup"), "config", "diffbot_controllers.yaml", ] diff --git a/launch/robot_localization.launch.py b/launch/robot_localization.launch.py index 04d2a31..97ca652 100644 --- a/launch/robot_localization.launch.py +++ b/launch/robot_localization.launch.py @@ -30,7 +30,7 @@ def generate_launch_description(): " ", PathJoinSubstitution( [ - FindPackageShare("bot_mini_description"), + FindPackageShare("cps_loki_description"), "urdf", "odrive_diffbot.urdf.xacro" ] @@ -41,7 +41,7 @@ def generate_launch_description(): robot_controllers = PathJoinSubstitution( [ - FindPackageShare("bot_mini_bringup"), + FindPackageShare("cps_loki_bringup"), "config", "diffbot_controllers.yaml", ] @@ -91,7 +91,7 @@ def generate_launch_description(): use_sim_time = False slam_params_file = PathJoinSubstitution( [ - FindPackageShare("bot_mini_bringup"), + FindPackageShare("cps_loki_bringup"), "config", "mapper_params_online_async.yaml" ] @@ -125,7 +125,7 @@ def generate_launch_description(): output='screen', parameters = [ PathJoinSubstitution( [ - FindPackageShare("bot_mini_bringup"), + FindPackageShare("cps_loki_bringup"), "config", "ekf.yaml" ] diff --git a/launch/robot_mapper.launch.py b/launch/robot_mapper.launch.py index 36c61eb..e969f6a 100644 --- a/launch/robot_mapper.launch.py +++ b/launch/robot_mapper.launch.py @@ -30,7 +30,7 @@ def generate_launch_description(): " ", PathJoinSubstitution( [ - FindPackageShare("bot_mini_description"), + FindPackageShare("cps_loki_description"), "urdf", "odrive_diffbot.urdf.xacro" ] @@ -41,7 +41,7 @@ def generate_launch_description(): robot_controllers = PathJoinSubstitution( [ - FindPackageShare("bot_mini_bringup"), + FindPackageShare("cps_loki_bringup"), "config", "diffbot_controllers.yaml", ] @@ -91,7 +91,7 @@ def generate_launch_description(): use_sim_time = False slam_params_file = PathJoinSubstitution( [ - FindPackageShare("bot_mini_bringup"), + FindPackageShare("cps_loki_bringup"), "config", "mapper_params_online_async.yaml" ] diff --git a/launch/robot_navigation.launch.py b/launch/robot_navigation.launch.py index f016df9..3c5ca58 100644 --- a/launch/robot_navigation.launch.py +++ b/launch/robot_navigation.launch.py @@ -28,7 +28,7 @@ from nav2_common.launch import RewrittenYaml def generate_launch_description(): # Get the launch directory - bringup_dir = get_package_share_directory('bot_mini_bringup') + bringup_dir = get_package_share_directory('cps_loki_bringup') namespace = LaunchConfiguration('namespace') use_sim_time = LaunchConfiguration('use_sim_time') diff --git a/launch/robot_twist_mux.launch.py b/launch/robot_twist_mux.launch.py index 33c1b01..013e231 100644 --- a/launch/robot_twist_mux.launch.py +++ b/launch/robot_twist_mux.launch.py @@ -29,7 +29,7 @@ def generate_launch_description(): " ", PathJoinSubstitution( [ - FindPackageShare("bot_mini_description"), + FindPackageShare("cps_loki_description"), "urdf", "odrive_diffbot.urdf.xacro" ] @@ -40,7 +40,7 @@ def generate_launch_description(): robot_controllers = PathJoinSubstitution( [ - FindPackageShare("bot_mini_bringup"), + FindPackageShare("cps_loki_bringup"), "config", "diffbot_controllers.yaml", ] @@ -99,7 +99,7 @@ def generate_launch_description(): parameters=[lidar_dir], ) - twist_mux_params = os.path.join(get_package_share_directory('bot_mini_bringup'),'config','twist_mux.yaml') + twist_mux_params = os.path.join(get_package_share_directory('cps_loki_bringup'),'config','twist_mux.yaml') twist_mux = Node( package="twist_mux", executable="twist_mux", diff --git a/launch/rsp.launch.py b/launch/rsp.launch.py index 172569f..83660c7 100644 --- a/launch/rsp.launch.py +++ b/launch/rsp.launch.py @@ -29,7 +29,7 @@ def generate_launch_description(): " ", PathJoinSubstitution( [ - FindPackageShare("bot_mini_description"), + FindPackageShare("cps_loki_description"), "urdf", "odrive_diffbot.urdf.xacro" ] diff --git a/launch/sim.launch.py b/launch/sim.launch.py index a8dcfa6..5799833 100644 --- a/launch/sim.launch.py +++ b/launch/sim.launch.py @@ -32,7 +32,7 @@ def generate_launch_description(): " ", PathJoinSubstitution( [ - FindPackageShare("bot_mini_description"), + FindPackageShare("cps_loki_description"), "urdf", "odrive_diffbot.urdf.xacro" ] @@ -43,7 +43,7 @@ def generate_launch_description(): robot_controllers = PathJoinSubstitution( [ - FindPackageShare("bot_mini_bringup"), + FindPackageShare("cps_loki_bringup"), "config", "diffbot_controllers.yaml", ] @@ -88,7 +88,7 @@ def generate_launch_description(): joystick_launch = IncludeLaunchDescription( PythonLaunchDescriptionSource([os.path.join( - get_package_share_directory('bot_mini_bringup'),'joy_teleop.launch.py' + get_package_share_directory('cps_loki_bringup'),'joy_teleop.launch.py' )]), launch_arguments={'use_sim_time': 'true'}.items() ) @@ -108,7 +108,7 @@ def generate_launch_description(): parameters=[lidar_dir], ) - twist_mux_params = os.path.join(get_package_share_directory('bot_mini_bringup'),'config','twist_mux.yaml') + twist_mux_params = os.path.join(get_package_share_directory('cps_loki_bringup'),'config','twist_mux.yaml') twist_mux = Node( package="twist_mux", executable="twist_mux", @@ -116,7 +116,7 @@ def generate_launch_description(): remappings=[('/cmd_vel_out','/diffbot_base_controller/cmd_vel_unstamped')] ) - gazebo_params_file = os.path.join(get_package_share_directory('bot_mini_bringup'),'config','gazebo_params.yaml') + gazebo_params_file = os.path.join(get_package_share_directory('cps_loki_bringup'),'config','gazebo_params.yaml') # Include the Gazebo launch file, provided by the gazebo_ros package gazebo = IncludeLaunchDescription( PythonLaunchDescriptionSource([os.path.join( diff --git a/launch/sim_bot_mini.launch.py b/launch/sim_bot_mini.launch.py index aa4c26c..dcdbd3d 100644 --- a/launch/sim_bot_mini.launch.py +++ b/launch/sim_bot_mini.launch.py @@ -48,7 +48,7 @@ def generate_launch_description(): rviz_config_file = PathJoinSubstitution( [ - FindPackageShare("bot_mini_bringup"), + FindPackageShare("cps_loki_bringup"), "config", "bot_mini.rviz" ] @@ -87,7 +87,7 @@ def generate_launch_description(): arguments=["-d", rviz_config_file], ) - package_name='bot_mini_bringup' + package_name='cps_loki_bringup' gazebo_params_file = os.path.join(get_package_share_directory(package_name),'config','gazebo_params.yaml') # Include the Gazebo launch file, provided by the gazebo_ros package From 35df61bd3390f151d3e75accb1b09cfdf28aea97 Mon Sep 17 00:00:00 2001 From: bjoernellens1 <64093272+bjoernellens1@users.noreply.github.com> Date: Mon, 20 Nov 2023 12:30:50 +0100 Subject: [PATCH 38/46] Update robot_lidar.launch.py --- launch/robot_lidar.launch.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/launch/robot_lidar.launch.py b/launch/robot_lidar.launch.py index cf4af81..92b3a08 100644 --- a/launch/robot_lidar.launch.py +++ b/launch/robot_lidar.launch.py @@ -87,7 +87,7 @@ def generate_launch_description(): executable="cam_node" ) - lidar_dir = os.path.join(get_package_share_directory('lslidar_driver'), 'params', 'lsx10.yaml') + lidar_dir = os.path.join(get_package_share_directory('cps_loki_bringup'), 'config', 'lsx10.yaml') lidar_node = LifecycleNode( package='lslidar_driver', executable='lslidar_driver_node', @@ -107,4 +107,4 @@ def generate_launch_description(): #teleop_spawner, #cam_node, lidar_node - ]) \ No newline at end of file + ]) From 0790288b666dabdca135e9a8b5d8072ac84b97d8 Mon Sep 17 00:00:00 2001 From: bjoernellens1 <64093272+bjoernellens1@users.noreply.github.com> Date: Mon, 20 Nov 2023 12:34:44 +0100 Subject: [PATCH 39/46] Create lsx10.yaml --- config/lsx10.yaml | 25 +++++++++++++++++++++++++ 1 file changed, 25 insertions(+) create mode 100644 config/lsx10.yaml diff --git a/config/lsx10.yaml b/config/lsx10.yaml new file mode 100644 index 0000000..d1197eb --- /dev/null +++ b/config/lsx10.yaml @@ -0,0 +1,25 @@ +/lslidar_driver_node: + ros__parameters: + frame_id: laser_frame #激光坐标 + group_ip: 224.1.1.2 + add_multicast: false + device_ip: 192.168.1.200 #雷达源IP + device_ip_difop: 192.168.1.102 #雷达目的ip + msop_port: 2368 #雷达目的端口号 + difop_port: 2369 #雷达源端口号 + lidar_name: N10 #雷达选择:M10 M10_P M10_PLUS M10_GPS N10 L10 N10_P + angle_disable_min: 0.0 #角度裁剪开始值 + angle_disable_max: 0.0 #角度裁剪结束值 + min_range: 0.0 #雷达接收距离最小值 + max_range: 200.0 #雷达接收距离最大值 + use_gps_ts: false #雷达是否使用GPS授时 + scan_topic: /scan #设置激光数据topic名称 + interface_selection: serial #接口选择:net 为网口,serial 为串口。 + serial_port_: /dev/ttyUSB0 #串口连接时的串口号 + high_reflection: false #M10_P雷达需填写该值,若不确定,请联系技术支持。 + compensation: false #M10系列是否使用角度补偿功能 + pubScan: true #是否发布scan话题 + pubPointCloud2: false #是否发布pointcloud2话题 + pointcloud_topic: /lslidar_point_cloud #设置激光数据topic名称 +# pcap: /home/ls/1.pcap #雷达是否使用pcap包读取功能 +# in_file_name: /home/ls/1.txt #雷达是否使用txt文件读取功能 From 6c655928c1284eb0d7de32cba989f3ef6aba0fd7 Mon Sep 17 00:00:00 2001 From: bjoernellens1 <64093272+bjoernellens1@users.noreply.github.com> Date: Wed, 22 Nov 2023 13:54:07 +0100 Subject: [PATCH 40/46] update --- config/nav2_params.yaml | 451 +--------------------------------------- 1 file changed, 7 insertions(+), 444 deletions(-) diff --git a/config/nav2_params.yaml b/config/nav2_params.yaml index cca2037..d0f2cd4 100644 --- a/config/nav2_params.yaml +++ b/config/nav2_params.yaml @@ -1,430 +1,3 @@ -# 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.05 -# 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: 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 - -# 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 - -# 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.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 - -# 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 -# plugins: ["voxel_layer", "inflation_layer"] -# inflation_layer: -# plugin: "nav2_costmap_2d::InflationLayer" -# cost_scaling_factor: 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: scan -# scan: -# topic: /scan -# 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 -# 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 -# 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 -# 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: 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 - -# 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: "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 -# deadband_velocity: [0.0, 0.0, 0.0] -# velocity_timeout: 1.0 - - - slam_toolbox: ros__parameters: @@ -440,7 +13,7 @@ slam_toolbox: odom_frame: odom map_frame: map base_frame: base_footprint - scan_topic: /scan + scan_topic: scan #scan_topic: /scan_filtered use_map_saver: true mode: mapping #localization @@ -547,7 +120,7 @@ bt_navigator: use_sim_time: True global_frame: map robot_base_frame: base_link - odom_topic: /odom + odom_topic: odom bt_loop_duration: 10 default_server_timeout: 20 # 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults: @@ -742,7 +315,7 @@ local_costmap: height: 3 resolution: 0.05 #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] ]" + footprint: "[ [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" @@ -759,7 +332,7 @@ local_costmap: mark_threshold: 0 observation_sources: scan scan: - topic: /scan + topic: scan max_obstacle_height: 2.0 clearing: True marking: True @@ -782,7 +355,7 @@ global_costmap: 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 + footprint: "[ [0.18, 0.255], [0.18, -0.255], [-0.54, -0.165], [-0.54, 0.165] ]" resolution: 0.05 track_unknown_space: true plugins: ["static_layer", "obstacle_layer", "inflation_layer"] @@ -791,7 +364,7 @@ global_costmap: enabled: True observation_sources: scan scan: - topic: /scan + topic: scan max_obstacle_height: 2.0 clearing: True marking: True @@ -824,16 +397,6 @@ map_saver: 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"] @@ -916,7 +479,7 @@ velocity_smoother: 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: "/odom" + odom_topic: "odom" odom_duration: 0.1 # was 0.1 deadband_velocity: [0.0, 0.0, 0.0] velocity_timeout: 1.0 From 7f305d64563fdbc602222ee7b608eadffd72f9ac Mon Sep 17 00:00:00 2001 From: bjoernellens1 <64093272+bjoernellens1@users.noreply.github.com> Date: Fri, 24 Nov 2023 09:37:22 +0100 Subject: [PATCH 41/46] update: inlcude scan filter node --- config/box_filter.yaml | 15 +++++++++++++++ launch/robot_scan_filter.launch.py | 18 ++++++++++++++++++ 2 files changed, 33 insertions(+) create mode 100644 config/box_filter.yaml create mode 100644 launch/robot_scan_filter.launch.py diff --git a/config/box_filter.yaml b/config/box_filter.yaml new file mode 100644 index 0000000..d4c184d --- /dev/null +++ b/config/box_filter.yaml @@ -0,0 +1,15 @@ +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.15 #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 \ No newline at end of file diff --git a/launch/robot_scan_filter.launch.py b/launch/robot_scan_filter.launch.py new file mode 100644 index 0000000..41dd487 --- /dev/null +++ b/launch/robot_scan_filter.launch.py @@ -0,0 +1,18 @@ +from launch import LaunchDescription +from launch.substitutions import PathJoinSubstitution +from launch_ros.actions import Node +from ament_index_python.packages import get_package_share_directory + + +def generate_launch_description(): + return LaunchDescription([ + Node( + package="laser_filters", + executable="scan_to_scan_filter_chain", + parameters=[ + PathJoinSubstitution([ + get_package_share_directory("cps_loki_bringup"), + "config", "box_filter.yaml", + ])], + ) + ]) \ No newline at end of file From 4bdc89d92bfa070f07e6240617d41cc36df095d0 Mon Sep 17 00:00:00 2001 From: bjoernellens1 <64093272+bjoernellens1@users.noreply.github.com> Date: Fri, 24 Nov 2023 09:38:40 +0100 Subject: [PATCH 42/46] update --- package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/package.xml b/package.xml index b4fb1a9..e4fc5a6 100644 --- a/package.xml +++ b/package.xml @@ -21,6 +21,7 @@ joy twist_mux robot_localization + laser_filters ament_python From 8e8153a2f8c0edc4a4db759cc6c621b4f8737540 Mon Sep 17 00:00:00 2001 From: bjoernellens1 <64093272+bjoernellens1@users.noreply.github.com> Date: Fri, 24 Nov 2023 09:51:23 +0100 Subject: [PATCH 43/46] update --- config/nav2_params.yaml | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/config/nav2_params.yaml b/config/nav2_params.yaml index d0f2cd4..b4bb56b 100644 --- a/config/nav2_params.yaml +++ b/config/nav2_params.yaml @@ -13,8 +13,8 @@ slam_toolbox: odom_frame: odom map_frame: map base_frame: base_footprint - scan_topic: scan - #scan_topic: /scan_filtered + #scan_topic: scan + scan_topic: scan_filtered use_map_saver: true mode: mapping #localization @@ -113,7 +113,7 @@ amcl: z_max: 0.05 z_rand: 0.5 z_short: 0.05 - scan_topic: scan + scan_topic: scan_filtered bt_navigator: ros__parameters: @@ -332,7 +332,7 @@ local_costmap: mark_threshold: 0 observation_sources: scan scan: - topic: scan + topic: scan_filtered max_obstacle_height: 2.0 clearing: True marking: True @@ -364,7 +364,7 @@ global_costmap: enabled: True observation_sources: scan scan: - topic: scan + topic: scan_filtered max_obstacle_height: 2.0 clearing: True marking: True From 26963afe415547497b8be752236f6314b7a151ea Mon Sep 17 00:00:00 2001 From: bjoernellens1 <64093272+bjoernellens1@users.noreply.github.com> Date: Fri, 24 Nov 2023 09:52:13 +0100 Subject: [PATCH 44/46] update --- config/mapper_params_online_async.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/config/mapper_params_online_async.yaml b/config/mapper_params_online_async.yaml index c50ffda..8cbe916 100644 --- a/config/mapper_params_online_async.yaml +++ b/config/mapper_params_online_async.yaml @@ -13,7 +13,7 @@ slam_toolbox: odom_frame: odom map_frame: map base_frame: base_footprint - scan_topic: /scan + scan_topic: scan_filtered mode: localization # if you'd like to immediately start continuing a map at a given pose From 1fa11fed73890defae5ddc1ec14bb9b791ea8cc5 Mon Sep 17 00:00:00 2001 From: bjoernellens1 <64093272+bjoernellens1@users.noreply.github.com> Date: Fri, 24 Nov 2023 11:25:44 +0100 Subject: [PATCH 45/46] update --- config/box_filter.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/config/box_filter.yaml b/config/box_filter.yaml index d4c184d..28f59bf 100644 --- a/config/box_filter.yaml +++ b/config/box_filter.yaml @@ -8,7 +8,7 @@ scan_to_scan_filter_chain: max_x: 0.80 #was 0.16 max_y: 0.18 #was 0.17 max_z: 0.1 - min_x: -0.15 #was -0.41 + min_x: -0.41 #was -0.41 min_y: -0.18 # was -0.17 min_z: -0.2 From efdad7087abb41bd56951f09c96621cb2849e730 Mon Sep 17 00:00:00 2001 From: bjoernellens1 <64093272+bjoernellens1@users.noreply.github.com> Date: Fri, 24 Nov 2023 11:34:22 +0100 Subject: [PATCH 46/46] update --- config/mapper_params_online_async.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/config/mapper_params_online_async.yaml b/config/mapper_params_online_async.yaml index 8cbe916..79528d8 100644 --- a/config/mapper_params_online_async.yaml +++ b/config/mapper_params_online_async.yaml @@ -14,7 +14,7 @@ slam_toolbox: map_frame: map base_frame: base_footprint scan_topic: scan_filtered - mode: localization + 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