diff --git a/CMakeLists.txt b/CMakeLists.txt
index 5313a42..243de51 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -1,39 +1,30 @@
-cmake_minimum_required(VERSION 3.16)
+cmake_minimum_required(VERSION 3.5)
project(turtlebot_flatland)
# Ensure we're using c++11
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11")
-## Find catkin macros and libraries
-## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
-## is used, also find other catkin packages
-find_package(catkin REQUIRED COMPONENTS
-)
-
+find_package(ament_cmake REQUIRED)
-catkin_package(
-)
###########
## Build ##
###########
-include_directories(
- ${catkin_INCLUDE_DIRS}
-)
-
install(DIRECTORY launch
- DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
+ DESTINATION share/${PROJECT_NAME}/
)
install(DIRECTORY maps
- DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
+ DESTINATION share/${PROJECT_NAME}/
)
install(DIRECTORY robot
- DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
+ DESTINATION share/${PROJECT_NAME}/
)
install(DIRECTORY rviz
- DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
+ DESTINATION share/${PROJECT_NAME}/
)
+
+ament_package()
diff --git a/launch/turtlebot_in_flatland.launch b/launch/turtlebot_in_flatland.launch
index 7cd7f9b..d1f1e49 100644
--- a/launch/turtlebot_in_flatland.launch
+++ b/launch/turtlebot_in_flatland.launch
@@ -26,80 +26,80 @@
You can override these default values:
roslaunch flatland_Server server.launch world_path:="/some/world.yaml" initial_rate:="30.0"
-->
-
+
-
+
-
+
-
+
-
-
-
-
-
+
+
+
+
+
-
+
+
+
+
+
+
+
-
-
-
-
-
+
+
+
+
+
-
-
+
+
-
-
-
-
-
-
-
+
+
+
+
+
+
+
-
-
-
-
+
+
+
+
-
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
-
-
+
+
diff --git a/launch/turtlebot_in_flatland.launch.py b/launch/turtlebot_in_flatland.launch.py
new file mode 100644
index 0000000..e149f7f
--- /dev/null
+++ b/launch/turtlebot_in_flatland.launch.py
@@ -0,0 +1,138 @@
+from launch import LaunchDescription
+from launch.actions import DeclareLaunchArgument, SetEnvironmentVariable, ExecuteProcess
+from launch.substitutions import LaunchConfiguration, PathJoinSubstitution, FindExecutable
+import launch.conditions as conditions
+from launch_ros.substitutions import FindPackageShare
+from launch_ros.actions import Node
+
+
+def generate_launch_description():
+ #pkg_share = get_package_share_directory("turtlebot_flatland")
+ pkg_share = FindPackageShare("turtlebot_flatland")
+
+ global_frame_id = LaunchConfiguration("global_frame_id")
+ min_obstacle_height = LaunchConfiguration("min_obstacle_height")
+ max_obstacle_height = LaunchConfiguration("max_obstacle_height")
+
+ initial_pose_x = LaunchConfiguration("initial_pose_x")
+ initial_pose_y = LaunchConfiguration("initial_pose_y")
+ initial_pose_a = LaunchConfiguration("initial_pose_a")
+
+ world_path = LaunchConfiguration("world_path")
+ update_rate = LaunchConfiguration("update_rate")
+ step_size = LaunchConfiguration("step_size")
+ show_viz = LaunchConfiguration("show_viz")
+ viz_pub_rate = LaunchConfiguration("viz_pub_rate")
+ use_sim_time = LaunchConfiguration("use_sim_time")
+
+ ld = LaunchDescription(
+ [
+ DeclareLaunchArgument(name="laser_topic", default_value="scan"), # default laser topic in flatland
+ DeclareLaunchArgument(name="odom_topic", default_value="odom"),
+ DeclareLaunchArgument(name="odom_frame_id", default_value="odom"),
+ DeclareLaunchArgument(name="base_frame_id", default_value="base"),
+ DeclareLaunchArgument(name="global_frame_id", default_value="map"),
+ # Name of the map to use (without path nor extension) and initial position
+ DeclareLaunchArgument(name="initial_pose_x", default_value="3.0"),
+ DeclareLaunchArgument(name="initial_pose_y", default_value="7.0"),
+ DeclareLaunchArgument(name="initial_pose_a", default_value="0.0"),
+ DeclareLaunchArgument(name="min_obstacle_height", default_value="0.0"),
+ DeclareLaunchArgument(name="max_obstacle_height", default_value="5.0"),
+
+ # ******************** flatland********************
+ # You can override these default values:
+ # roslaunch flatland_Server server.launch world_path:="/some/world.yaml" initial_rate:="30.0"
+ DeclareLaunchArgument(
+ name="world_path",
+ default_value=PathJoinSubstitution([pkg_share, "maps/hospital_section.world.yaml"]),
+ ),
+ DeclareLaunchArgument(name="update_rate", default_value="100.0"),
+ DeclareLaunchArgument(name="step_size", default_value="0.01"),
+ DeclareLaunchArgument(name="show_viz", default_value="true"),
+ DeclareLaunchArgument(name="viz_pub_rate", default_value="30.0"),
+ DeclareLaunchArgument(name="use_sim_time", default_value="true"),
+
+ SetEnvironmentVariable(name="ROSCONSOLE_FORMAT", value="[${severity} ${time} ${logger}]: ${message}"),
+
+ # launch flatland server
+ Node(
+ name="flatland_server",
+ package="flatland_server",
+ executable="flatland_server",
+ output="screen",
+ parameters=[
+ # Use the arguments passed into the launchfile for this node
+ {"world_path": world_path},
+ {"update_rate": update_rate},
+ {"step_size": step_size},
+ {"show_viz": show_viz},
+ {"viz_pub_rate": viz_pub_rate},
+ {"use_sim_time": use_sim_time},
+ ],
+ ),
+
+ # ***************** Robot Model *****************
+ ExecuteProcess(
+ cmd=[[
+ FindExecutable(name='ros2'),
+ " service ",
+ "call ",
+ "/spawn_model ",
+ "flatland_msgs/srv/SpawnModel ",
+ "\"{yaml_path: '", PathJoinSubstitution([pkg_share, 'robot/turtlebot.model.yaml']),
+ "', name: 'turtlebot0', ns: '', pose: ",
+ "{x: ", initial_pose_x, ", y: ", initial_pose_y, ", theta: ", initial_pose_a, "}}\"",
+ ]],
+ shell=True,
+ ),
+
+ # ****** Maps *****
+ Node(
+ name="map_server",
+ package="nav2_map_server",
+ executable="map_server",
+ output='screen',
+ parameters=[
+ {"yaml_filename": PathJoinSubstitution([pkg_share, "maps/hospital_section.yaml"])},
+ {"frame_id": global_frame_id},
+ ],
+ ),
+ Node(
+ name='lifecycle_manager_navigation',
+ package='nav2_lifecycle_manager',
+ executable='lifecycle_manager',
+ output='screen',
+ parameters=[
+ {'autostart': False},
+ {'node_names': ["map_server"]},
+ ],
+ ),
+ Node(
+ name="tf",
+ package="tf2_ros",
+ executable="static_transform_publisher",
+ arguments=["0", "0", "0", "0", "0", "0", "map", "odom"],
+ ),
+
+ # ***************** Manually setting some parameters *************************
+ DeclareLaunchArgument(name="move_base/local_costmap/obstacle_layer/scan/min_obstacle_height", default_value=min_obstacle_height),
+ DeclareLaunchArgument(name="move_base/local_costmap/obstacle_layer/scan/max_obstacle_height", default_value=max_obstacle_height),
+ DeclareLaunchArgument(name="move_base/global_costmap/obstacle_layer/scan/min_obstacle_height", default_value=min_obstacle_height),
+ DeclareLaunchArgument(name="move_base/global_costmap/obstacle_layer/scan/max_obstacle_height", default_value=max_obstacle_height),
+
+ # **************** Visualisation ****************
+ Node(
+ name="rviz",
+ package="rviz2",
+ executable="rviz2",
+ arguments=["-d", PathJoinSubstitution([pkg_share, "rviz/robot_navigation.rviz"])],
+ parameters=[{"use_sim_time": use_sim_time}],
+ condition=conditions.IfCondition(show_viz),
+ ),
+ ]
+ )
+ return ld
+
+
+if __name__ == "__main__":
+ generate_launch_description()
diff --git a/package.xml b/package.xml
index 1c3ae22..bebf0b3 100644
--- a/package.xml
+++ b/package.xml
@@ -10,13 +10,16 @@
Joseph Duchesne
BSD
+ ament_cmake
- catkin
- flatland_msgs
- flatland_plugins
- navigation
- turtlebot_bringup
- turtlebot_navigation
- yocs_virtual_sensor
- yocs_velocity_smoother
+
+
+ nav2_map_server
+ nav2_rviz_plugins
+ turtlebot3_bringup
+ turtlebot3_navigation2
+
+
+
+ ament_cmake
diff --git a/rviz/robot_navigation.rviz b/rviz/robot_navigation.rviz
index f6ff3ba..32b247a 100644
--- a/rviz/robot_navigation.rviz
+++ b/rviz/robot_navigation.rviz
@@ -1,5 +1,5 @@
Panels:
- - Class: rviz/Displays
+ - Class: rviz_common/Displays
Help Height: 78
Name: Displays
Property Tree Widget:
@@ -11,31 +11,33 @@ Panels:
- /Global Planning1
Splitter Ratio: 0.5
Tree Height: 595
- - Class: rviz/Selection
+ - Class: rviz_common/Selection
Name: Selection
- - Class: rviz/Tool Properties
+ - Class: rviz_common/Tool Properties
Expanded:
- /2D Pose Estimate1
- /2D Nav Goal1
Name: Tool Properties
Splitter Ratio: 0.588679016
- - Class: rviz/Views
+ - Class: rviz_common/Views
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
- - Class: rviz/Time
+ - Class: rviz_common/Time
Experimental: false
Name: Time
SyncMode: 0
SyncSource: LaserScan (kinect)
+ - Class: nav2_rviz_plugins/Navigation 2
+ Name: Navigation 2
Visualization Manager:
Class: ""
Displays:
- - Alpha: 0.5
+ - Alpha: 0.1
Cell Size: 1
- Class: rviz/Grid
- Color: 160; 160; 164
+ Class: rviz_default_plugins/Grid
+ Color: 224; 224; 224
Enabled: true
Line Style:
Line Width: 0.0299999993
@@ -47,10 +49,10 @@ Visualization Manager:
Y: 0
Z: 0
Plane: XY
- Plane Cell Count: 10
+ Plane Cell Count: 100
Reference Frame:
Value: true
- - Class: rviz/TF
+ - Class: rviz_default_plugins/TF
Enabled: false
Frame Timeout: 15
Frames:
@@ -72,7 +74,7 @@ Visualization Manager:
Value: true
Axis: Z
Channel Name: intensity
- Class: rviz/LaserScan
+ Class: rviz_default_plugins/LaserScan
Color: 255; 0; 0
Color Transformer: FlatColor
Decay Time: 0
@@ -102,7 +104,7 @@ Visualization Manager:
Value: true
Axis: Z
Channel Name: intensity
- Class: rviz/LaserScan
+ Class: rviz_default_plugins/LaserScan
Color: 255; 255; 255
Color Transformer: Intensity
Decay Time: 0
@@ -125,19 +127,19 @@ Visualization Manager:
Use rainbow: true
Value: true
- Alpha: 0.699999988
- Class: rviz/Map
+ Class: rviz_default_plugins/Map
Color Scheme: map
Draw Behind: false
- Enabled: false
+ Enabled: true
Name: Map
Topic: /map
Unreliable: false
Use Timestamp: false
Value: false
- - Class: rviz/Group
+ - Class: rviz_common/Group
Displays:
- Alpha: 0.699999988
- Class: rviz/Map
+ Class: rviz_default_plugins/Map
Color Scheme: costmap
Draw Behind: false
Enabled: true
@@ -148,7 +150,7 @@ Visualization Manager:
Value: true
- Alpha: 1
Buffer Length: 1
- Class: rviz/Path
+ Class: rviz_default_plugins/Path
Color: 0; 12; 255
Enabled: true
Head Diameter: 0.300000012
@@ -177,7 +179,7 @@ Visualization Manager:
Value: true
Axis: Z
Channel Name: goal_cost
- Class: rviz/PointCloud2
+ Class: rviz_default_plugins/PointCloud2
Color: 255; 255; 255
Color Transformer: Intensity
Decay Time: 0
@@ -207,7 +209,7 @@ Visualization Manager:
Value: true
Axis: Z
Channel Name: total_cost
- Class: rviz/PointCloud2
+ Class: rviz_default_plugins/PointCloud2
Color: 255; 255; 255
Color Transformer: Intensity
Decay Time: 0
@@ -231,10 +233,10 @@ Visualization Manager:
Value: true
Enabled: true
Name: Local Planning
- - Class: rviz/Group
+ - Class: rviz_common/Group
Displays:
- Alpha: 0.400000006
- Class: rviz/Map
+ Class: rviz_default_plugins/Map
Color Scheme: costmap
Draw Behind: true
Enabled: true
@@ -245,7 +247,7 @@ Visualization Manager:
Value: true
- Alpha: 1
Buffer Length: 1
- Class: rviz/Path
+ Class: rviz_default_plugins/Path
Color: 255; 0; 0
Enabled: true
Head Diameter: 0.300000012
@@ -271,7 +273,7 @@ Visualization Manager:
- Alpha: 1
Axes Length: 1
Axes Radius: 0.100000001
- Class: rviz/Pose
+ Class: rviz_default_plugins/Pose
Color: 255; 25; 0
Enabled: true
Head Length: 0.200000003
@@ -287,7 +289,7 @@ Visualization Manager:
Arrow Length: 0.200000003
Axes Length: 0.300000012
Axes Radius: 0.00999999978
- Class: rviz/PoseArray
+ Class: rviz_default_plugins/PoseArray
Color: 0; 192; 0
Enabled: true
Head Length: 0.0700000003
@@ -301,7 +303,7 @@ Visualization Manager:
Value: true
- Alpha: 1
Buffer Length: 1
- Class: rviz/Path
+ Class: rviz_default_plugins/Path
Color: 25; 255; 0
Enabled: true
Head Diameter: 0.300000012
@@ -323,7 +325,7 @@ Visualization Manager:
Unreliable: false
Value: true
- Angle Tolerance: 0.100000001
- Class: rviz/Odometry
+ Class: rviz_default_plugins/Odometry
Covariance:
Orientation:
Alpha: 0.5
@@ -356,25 +358,32 @@ Visualization Manager:
Topic: /odom
Unreliable: false
Value: false
- - Class: rviz/MarkerArray
+ - Class: rviz_default_plugins/MarkerArray
Enabled: false
- Marker Topic: /move_base/EBandPlannerROS/eband_visualization_array
+ Topic:
+ Value: /move_base/EBandPlannerROS/eband_visualization_array
Name: EBand boubles
Namespaces:
{}
Queue Size: 100
Value: false
- - Class: rviz/MarkerArray
+ - Class: rviz_default_plugins/MarkerArray
Enabled: true
- Marker Topic: /flatland_server/debug/layer/2d
+ Topic:
+ Value: /layers/l_2d
+ Depth: 1
+ History Policy: Keep Last
+ Reliability Policy: Reliable
+ Durability Policy: Transient Local
Name: World
Namespaces:
"": true
Queue Size: 100
Value: true
- - Class: rviz/MarkerArray
+ - Class: rviz_default_plugins/MarkerArray
Enabled: true
- Marker Topic: /flatland_server/debug/model/turtlebot0
+ Topic:
+ Value: /models/m_turtlebot0
Name: Turtlebot
Namespaces:
"": true
@@ -388,7 +397,7 @@ Visualization Manager:
Value: true
Axis: Z
Channel Name: intensity
- Class: rviz/LaserScan
+ Class: rviz_default_plugins/LaserScan
Color: 255; 170; 0
Color Transformer: FlatColor
Decay Time: 0
@@ -410,30 +419,32 @@ Visualization Manager:
Use Fixed Frame: true
Use rainbow: true
Value: true
- - Class: rviz/MarkerArray
+ - Class: rviz_default_plugins/MarkerArray
Enabled: true
- Marker Topic: /flatland_server/debug/model/table0
- Name: MarkerArray
+ Topic:
+ Value: /models/m_table0
+ Name: Table
Namespaces:
"": true
Queue Size: 100
Value: true
- - Class: rviz/MarkerArray
+ - Class: rviz_default_plugins/MarkerArray
Enabled: true
- Marker Topic: /flatland_server/debug/model/door0
- Name: MarkerArray
+ Topic:
+ Value: /models/m_door0
+ Name: Door
Namespaces:
"": true
Queue Size: 100
Value: true
- - Class: rviz/InteractiveMarkers
+ - Class: rviz_default_plugins/InteractiveMarkers
Enable Transparency: true
Enabled: true
+ Interactive Markers Namespace: /interactive_model_markers
Name: InteractiveMarkers
Show Axes: false
Show Descriptions: true
Show Visual Aids: false
- Update Topic: /interactive_model_markers/update
Value: true
Enabled: true
Global Options:
@@ -442,20 +453,23 @@ Visualization Manager:
Frame Rate: 30
Name: root
Tools:
- - Class: rviz/MoveCamera
- - Class: rviz/Interact
+ - Class: rviz_default_plugins/MoveCamera
+ - Class: flatland_rviz_plugins/Interact
Hide Inactive Objects: true
- - Class: rviz/Select
- - Class: rviz/SetInitialPose
+ - Class: flatland_rviz_plugins/TogglePause
+ - Class: flatland_rviz_plugins/SpawnModel
+ - Class: flatland_rviz_plugins/ChangeRate
+ - Class: rviz_default_plugins/Select
+ - Class: rviz_default_plugins/SetInitialPose
Topic: /initialpose
- - Class: rviz/SetGoal
+ - Class: rviz_default_plugins/SetGoal
Topic: /move_base_simple/goal
- - Class: rviz/Measure
+ - Class: rviz_default_plugins/Measure
Value: true
Views:
Current:
Angle: 0
- Class: rviz/TopDownOrtho
+ Class: rviz_default_plugins/TopDownOrtho
Enable Stereo Rendering:
Stereo Eye Separation: 0.0599999987
Stereo Focal Distance: 1