diff --git a/nav2_minimal_tb4_description/urdf/icreate/common_properties.urdf.xacro b/nav2_minimal_tb4_description/urdf/icreate/common_properties.urdf.xacro index 954ae8c..4810fe4 100644 --- a/nav2_minimal_tb4_description/urdf/icreate/common_properties.urdf.xacro +++ b/nav2_minimal_tb4_description/urdf/icreate/common_properties.urdf.xacro @@ -48,8 +48,9 @@ ${update_rate} @@ -65,6 +66,14 @@ ${h_min_angle} ${h_max_angle} + + + ${v_samples} + ${v_res} + ${v_min_angle} + ${v_max_angle} + + ${r_min} diff --git a/nav2_minimal_tb4_description/urdf/sensors/velodyne.urdf.xacro b/nav2_minimal_tb4_description/urdf/sensors/velodyne.urdf.xacro new file mode 100644 index 0000000..bcdf6ab --- /dev/null +++ b/nav2_minimal_tb4_description/urdf/sensors/velodyne.urdf.xacro @@ -0,0 +1,53 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + true + + + + diff --git a/nav2_minimal_tb4_description/urdf/standard/turtlebot4.urdf.xacro b/nav2_minimal_tb4_description/urdf/standard/turtlebot4.urdf.xacro index 40a286a..a7c833f 100644 --- a/nav2_minimal_tb4_description/urdf/standard/turtlebot4.urdf.xacro +++ b/nav2_minimal_tb4_description/urdf/standard/turtlebot4.urdf.xacro @@ -3,6 +3,7 @@ + @@ -130,10 +131,21 @@ - - - + + + + + + + + + + + + + diff --git a/nav2_minimal_tb4_sim/launch/simulation.launch.py b/nav2_minimal_tb4_sim/launch/simulation.launch.py index c4cc525..70af256 100644 --- a/nav2_minimal_tb4_sim/launch/simulation.launch.py +++ b/nav2_minimal_tb4_sim/launch/simulation.launch.py @@ -54,6 +54,7 @@ def generate_launch_description(): use_simulator = LaunchConfiguration('use_simulator') use_robot_state_pub = LaunchConfiguration('use_robot_state_pub') headless = LaunchConfiguration('headless') + use_3dlidar = LaunchConfiguration('use_3dlidar') world = LaunchConfiguration('world') pose = { 'x': LaunchConfiguration('x_pose', default='-8.00'), @@ -113,6 +114,12 @@ def generate_launch_description(): 'headless', default_value='False', description='Whether to execute gzclient)' ) + declare_use_3dlidar_cmd = DeclareLaunchArgument( + 'use_3dlidar', + default_value='False', + description='Whether to use 3D Lidar and publish pointcloud2' + ) + declare_world_cmd = DeclareLaunchArgument( 'world', default_value=os.path.join(sim_dir, 'worlds', 'depot.sdf'), @@ -138,7 +145,9 @@ def generate_launch_description(): output='screen', parameters=[ {'use_sim_time': use_sim_time, - 'robot_description': Command(['xacro', ' ', robot_sdf])} + 'robot_description': Command( + ['xacro', ' ', 'use_3d_lidar:=', use_3dlidar, ' ', robot_sdf] + )} ], remappings=remappings, ) @@ -196,6 +205,7 @@ def generate_launch_description(): launch_arguments={'namespace': namespace, 'use_simulator': use_simulator, 'use_sim_time': use_sim_time, + 'use_3dlidar': use_3dlidar, 'robot_name': robot_name, 'robot_sdf': robot_sdf, 'x_pose': pose['x'], @@ -217,6 +227,7 @@ def generate_launch_description(): ld.add_action(declare_use_simulator_cmd) ld.add_action(declare_use_robot_state_pub_cmd) ld.add_action(declare_simulator_cmd) + ld.add_action(declare_use_3dlidar_cmd) ld.add_action(declare_world_cmd) ld.add_action(declare_robot_name_cmd) ld.add_action(declare_robot_sdf_cmd) diff --git a/nav2_minimal_tb4_sim/launch/spawn_tb4.launch.py b/nav2_minimal_tb4_sim/launch/spawn_tb4.launch.py index 3325bc9..e179657 100644 --- a/nav2_minimal_tb4_sim/launch/spawn_tb4.launch.py +++ b/nav2_minimal_tb4_sim/launch/spawn_tb4.launch.py @@ -31,6 +31,7 @@ def generate_launch_description(): use_sim_time = LaunchConfiguration('use_sim_time') namespace = LaunchConfiguration('namespace') use_simulator = LaunchConfiguration('use_simulator') + use_3dlidar = LaunchConfiguration('use_3dlidar') robot_name = LaunchConfiguration('robot_name') # robot_sdf = LaunchConfiguration('robot_sdf') pose = {'x': LaunchConfiguration('x_pose', default='-8.00'), @@ -51,6 +52,12 @@ def generate_launch_description(): default_value='True', description='Whether to start the simulator') + declare_use_3dlidar_cmd = DeclareLaunchArgument( + 'use_3dlidar', + default_value='False', + description='Whether to use 3D Lidar and publish pointcloud2' + ) + declare_use_sim_time_cmd = DeclareLaunchArgument( 'use_sim_time', default_value='true', @@ -78,6 +85,24 @@ def generate_launch_description(): output='screen', ) + # replace [ros_gz_point_cloud that only works with ign-gazebo <= 2.6.1] + # https://github.com/gazebosim/ros_gz/issues/40 + pcl_bridge = Node( + condition=IfCondition(use_3dlidar), + package='ros_gz_bridge', + executable='parameter_bridge', + name='bridge_ros_gz_pcl', + namespace=namespace, + output='screen', + parameters=[{ + 'use_sim_time': use_sim_time, + }], + remappings=[ + ('/scan/points', '/pointcloud') + ], + arguments=['/scan/points@sensor_msgs/msg/PointCloud2[gz.msgs.PointCloudPacked'], + ) + camera_bridge_image = Node( package='ros_gz_image', executable='image_bridge', @@ -119,9 +144,11 @@ def generate_launch_description(): ld.add_action(declare_namespace_cmd) ld.add_action(declare_robot_name_cmd) ld.add_action(declare_use_simulator_cmd) + ld.add_action(declare_use_3dlidar_cmd) ld.add_action(declare_use_sim_time_cmd) ld.add_action(bridge) + ld.add_action(pcl_bridge) ld.add_action(camera_bridge_image) ld.add_action(camera_bridge_depth) ld.add_action(spawn_model)