added slam and nav2
This commit is contained in:
parent
77126a8dc6
commit
80eb936283
195
docs/General ROS 2/SLAM and Navigation/Commander API.md
Executable file
195
docs/General ROS 2/SLAM and Navigation/Commander API.md
Executable file
@ -0,0 +1,195 @@
|
||||
# Commander API
|
||||
## What is the Commander API
|
||||
The **Commander API** in **ROS 2 Navigation Stack (Nav2)** is a Python interface for programmatically controlling a robot’s navigation behavior. It simplifies interaction with the Nav2 stack by providing an intuitive, high-level API for sending navigation goals, controlling the robot, and monitoring progress.
|
||||
|
||||
|
||||
## Installing
|
||||
|
||||
```bash
|
||||
sudo apt install ros-humble-tf-transformations
|
||||
sudo apt install python3-transforms3d
|
||||
```
|
||||
|
||||
## Tips and Tricks
|
||||
Here are a few tips and tricks I find useful
|
||||
### Getting Click Coordinates
|
||||
It might seem hard to get the coordinates to navigate to. If you launch the navigation package and then open a terminal and subscribe to `/clicked_point` then you can go to the top bar in rviz2 and click on publish points and then wherever you click next will get published on the `/clicked_point` topic.
|
||||
```bash
|
||||
ros2 topic echo /clicked_point
|
||||
```
|
||||
### Getting Mouse Position
|
||||
Another way to get the coordinates on a map in rviz2 is to use the `Focus Camera` button on the top bar of rviz2 to display the coordinates of the mouse in the bottom left-hand corner.
|
||||
|
||||
|
||||
## Python Script
|
||||
### Setting Initial Pose
|
||||
To set and initial pose use the `setInitialPose()` command to send the initial pose to the correct ROS2 node.
|
||||
|
||||
```python linenums="1"
|
||||
q_x, q_y, q_z, q_w = tf_transformations.quaternion_from_euler(0.0, 0.0, 0.0)
|
||||
|
||||
initial_pose = PoseStamped()
|
||||
initial_pose.header.frame_id ='map'
|
||||
initial_pose.header.stamp = navigator.get_clock().now().to_msg()
|
||||
initial_pose.pose.position.x = position_x
|
||||
initial_pose.pose.position.y = position_y
|
||||
initial_pose.pose.position.z = 0.0
|
||||
initial_pose.pose.orientation.x = q_x
|
||||
initial_pose.pose.orientation.y = q_y
|
||||
initial_pose.pose.orientation.z = q_z
|
||||
initial_pose.pose.orientation.w = q_w
|
||||
|
||||
nav.goToPose(initial_pose)
|
||||
```
|
||||
|
||||
### Navigating to a Goal
|
||||
To navigate to a goal first get the `goal_pose` then use the `goToPose` command to navigate to that specific pose.
|
||||
|
||||
```python linenums="1"
|
||||
def create_pose_stamped(navigator: BasicNavigator, position_x: float, position_y: float, orientation_z: float):
|
||||
if math.fabs(orientation_z) > 2*math.pi:
|
||||
# convert from degrees to radian
|
||||
orientation_z = orientation_z * math.pi / 180
|
||||
q_x, q_y, q_z, q_w = tf_transformations.quaternion_from_euler(0.0, 0.0, orientation_z)
|
||||
pose = PoseStamped()
|
||||
pose.header.frame_id ='map'
|
||||
pose.header.stamp = navigator.get_clock().now().to_msg()
|
||||
pose.pose.position.x = position_x
|
||||
pose.pose.position.y = position_y
|
||||
pose.pose.position.z = 0.0
|
||||
pose.pose.orientation.x = q_x
|
||||
pose.pose.orientation.y = q_y
|
||||
pose.pose.orientation.z = q_z
|
||||
pose.pose.orientation.w = q_w
|
||||
return pose
|
||||
|
||||
# --- Send Nav2 goal
|
||||
goal_pose = create_pose_stamped(nav, 1.72, 0.37, 1.57)
|
||||
nav.goToPose(goal_pose)
|
||||
# --- Wait for Nav2
|
||||
while not nav.isTaskComplete():
|
||||
feedback = nav.getFeedback()
|
||||
print(f"Distance remaining: {feedback.distance_remaining:.2f} meters")
|
||||
time.sleep(1)
|
||||
# --- Print Success
|
||||
print(nav.getResult())
|
||||
```
|
||||
|
||||
### Navigating Waypoints
|
||||
To navigate to a list of points use the `followWaypoints` command in the commander API and give it a array of `PoseStamped()`.
|
||||
|
||||
```python linenums="1"
|
||||
def create_pose_stamped(navigator: BasicNavigator, position_x: float, position_y: float, orientation_z: float):
|
||||
if math.fabs(orientation_z) > 2*math.pi:
|
||||
# convert from degrees to radian
|
||||
orientation_z = orientation_z * math.pi / 180
|
||||
q_x, q_y, q_z, q_w = tf_transformations.quaternion_from_euler(0.0, 0.0, orientation_z)
|
||||
pose = PoseStamped()
|
||||
pose.header.frame_id ='map'
|
||||
pose.header.stamp = navigator.get_clock().now().to_msg()
|
||||
pose.pose.position.x = position_x
|
||||
pose.pose.position.y = position_y
|
||||
pose.pose.position.z = 0.0
|
||||
pose.pose.orientation.x = q_x
|
||||
pose.pose.orientation.y = q_y
|
||||
pose.pose.orientation.z = q_z
|
||||
pose.pose.orientation.w = q_w
|
||||
return pose
|
||||
|
||||
# --- Send Follow waypoints
|
||||
goal_pose1 = create_pose_stamped(nav, 0.226, 2.0, 180)
|
||||
goal_pose2 = create_pose_stamped(nav, -0.55, 0.58, 270)
|
||||
goal_pose3 = create_pose_stamped(nav, 0.59, -1.81, 0)
|
||||
goal_pose4 = create_pose_stamped(nav, -2.0, -0.5, 0)
|
||||
waypoints = [goal_pose1, goal_pose2, goal_pose3, goal_pose4]
|
||||
nav.followWaypoints(waypoints)
|
||||
# --- Wait for Nav2
|
||||
while not nav.isTaskComplete():
|
||||
feedback = nav.getFeedback()
|
||||
print(feedback)
|
||||
time.sleep(1)
|
||||
# --- Print Success
|
||||
print(nav.getResult())
|
||||
```
|
||||
|
||||
|
||||
### Full Script
|
||||
Here is a full example of a python script that drives the Turtlebot3 around its world:
|
||||
|
||||
```python title="nav2_turtlebot3_loop.py" linenums="1"
|
||||
#!/usr/bin/env python3
|
||||
import rclpy
|
||||
from nav2_simple_commander.robot_navigator import BasicNavigator
|
||||
from geometry_msgs.msg import PoseStamped
|
||||
import tf_transformations
|
||||
import time, math
|
||||
|
||||
|
||||
def create_pose_stamped(navigator: BasicNavigator, position_x: float, position_y: float, orientation_z: float):
|
||||
if math.fabs(orientation_z) > 2*math.pi:
|
||||
# convert from degrees to radian
|
||||
orientation_z = orientation_z * math.pi / 180
|
||||
|
||||
q_x, q_y, q_z, q_w = tf_transformations.quaternion_from_euler(0.0, 0.0, orientation_z)
|
||||
|
||||
pose = PoseStamped()
|
||||
pose.header.frame_id ='map'
|
||||
pose.header.stamp = navigator.get_clock().now().to_msg()
|
||||
pose.pose.position.x = position_x
|
||||
pose.pose.position.y = position_y
|
||||
pose.pose.position.z = 0.0
|
||||
pose.pose.orientation.x = q_x
|
||||
pose.pose.orientation.y = q_y
|
||||
pose.pose.orientation.z = q_z
|
||||
pose.pose.orientation.w = q_w
|
||||
|
||||
return pose
|
||||
|
||||
|
||||
def main():
|
||||
# --- Init
|
||||
rclpy.init()
|
||||
nav = BasicNavigator()
|
||||
|
||||
# --- Set initial Pose
|
||||
initial_pose = create_pose_stamped(nav, -2.0, -0.5, 0)
|
||||
nav.setInitialPose(initial_pose)
|
||||
|
||||
# --- Wait for Nav2
|
||||
nav.waitUntilNav2Active()
|
||||
|
||||
# --- Send Nav2 goal
|
||||
goal_pose = create_pose_stamped(nav, 1.72, 0.37, 1.57)
|
||||
nav.goToPose(goal_pose)
|
||||
# --- Wait for Nav2
|
||||
while not nav.isTaskComplete():
|
||||
feedback = nav.getFeedback()
|
||||
print(f"Distance remaining: {feedback.distance_remaining:.2f} meters")
|
||||
time.sleep(1)
|
||||
# --- Print Success
|
||||
print(nav.getResult())
|
||||
|
||||
# --- Send Follow waypoints
|
||||
goal_pose1 = create_pose_stamped(nav, 0.226, 2.0, 180)
|
||||
goal_pose2 = create_pose_stamped(nav, -0.55, 0.58, 270)
|
||||
goal_pose3 = create_pose_stamped(nav, 0.59, -1.81, 0)
|
||||
goal_pose4 = create_pose_stamped(nav, -2.0, -0.5, 0)
|
||||
waypoints = [goal_pose1, goal_pose2, goal_pose3, goal_pose4]
|
||||
nav.followWaypoints(waypoints)
|
||||
# --- Wait for Nav2
|
||||
while not nav.isTaskComplete():
|
||||
feedback = nav.getFeedback()
|
||||
print(feedback)
|
||||
time.sleep(1)
|
||||
# --- Print Success
|
||||
print(nav.getResult())
|
||||
|
||||
# --- Shutdown
|
||||
nav.lifecycleShutdown()
|
||||
rclpy.shutdown()
|
||||
|
||||
if __name__ == '__main__':
|
||||
main()
|
||||
```
|
||||
## More Help
|
||||
For additional help visit this [site](https://docs.nav2.org/commander_api/index.html).
|
97
docs/General ROS 2/SLAM and Navigation/Nav2.md
Executable file
97
docs/General ROS 2/SLAM and Navigation/Nav2.md
Executable file
@ -0,0 +1,97 @@
|
||||
# Nav2
|
||||
## What is Nav2
|
||||
**Nav2**, or the **Navigation 2 Stack**, is a powerful and flexible navigation framework for robots in the **Robot Operating System 2 (ROS 2)**. It provides a modular set of tools and algorithms for autonomous robot navigation in complex environments.
|
||||
|
||||
## Starting Nav2 from the Terminal
|
||||
Here are the terminal commands for launching the Nav2 toolkit.
|
||||
|
||||
```bash
|
||||
# Start robot or robot simulator in this case I wil use the turtlebot3
|
||||
ros2 launch turtlebot3_gazebo turtlebot3_world.launch.py
|
||||
|
||||
ros2 launch nav2_bringup bringup_launch.py use_sim_time:=true map:=Desktop/maps/my_map.yaml
|
||||
# Launch rviz2 and add the TF visualization and the map visualization
|
||||
ros2 run rviz2 rviz2
|
||||
```
|
||||
|
||||
## Custom Nav2 Launch File
|
||||
Here is a custom ROS 2 Launch file
|
||||
|
||||
=== "Python"
|
||||
|
||||
```python title="nav2.launch.py" linenums="1"
|
||||
from launch import LaunchDescription
|
||||
import os
|
||||
from ament_index_python import get_package_share_directory
|
||||
from launch_ros.parameter_descriptions import ParameterValue
|
||||
from launch.substitutions import LaunchConfiguration
|
||||
from launch_ros.actions import Node
|
||||
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
|
||||
|
||||
def generate_launch_description():
|
||||
|
||||
# Declare the arguments
|
||||
use_sim_time = LaunchConfiguration('use_sim_time', default='False')
|
||||
map = LaunchConfiguration('map')
|
||||
|
||||
# Define RViz config path
|
||||
rviz_config_path = os.path.join(
|
||||
get_package_share_directory('locker98_tools_bringup'),
|
||||
'rviz', 'nav2_config.rviz'
|
||||
)
|
||||
|
||||
# Include the bringup launch file
|
||||
bringup_launch_file = os.path.join(
|
||||
get_package_share_directory('nav2_bringup'),
|
||||
'launch', 'bringup_launch.py'
|
||||
)
|
||||
|
||||
# Include the bringup launch file and pass arguments
|
||||
include_bringup = IncludeLaunchDescription(
|
||||
bringup_launch_file,
|
||||
launch_arguments={
|
||||
'use_sim_time': use_sim_time,
|
||||
'map': map
|
||||
}.items()
|
||||
)
|
||||
|
||||
# RViz node
|
||||
rviz2_node = Node(
|
||||
package='rviz2',
|
||||
executable='rviz2',
|
||||
output='screen',
|
||||
arguments=['-d', rviz_config_path]
|
||||
)
|
||||
|
||||
# Return LaunchDescription
|
||||
return LaunchDescription([
|
||||
DeclareLaunchArgument('use_sim_time', default_value='False', description='Use simulation time'),
|
||||
DeclareLaunchArgument('map', default_value='', description='Map input'),
|
||||
include_bringup,
|
||||
rviz2_node
|
||||
])
|
||||
```
|
||||
|
||||
=== "XML"
|
||||
|
||||
This is the XML version that is much easier to understand but for some reason it does not work. There is some error with the args the makes it error every time I try to build it.
|
||||
|
||||
```xml title="nav2.launch.xml" linenums="1"
|
||||
<?xml version="1.0"?>
|
||||
<launch>
|
||||
<!-- Declare Launch Arguments -->
|
||||
<arg name="use_sim_time" default="false" description="Use simulation time" />
|
||||
<arg name="map" default="" description="Map input" />
|
||||
|
||||
<!-- Include bringup launch file -->
|
||||
<include file="$(find-pkg-share nav2_bringup)/launch/bringup_launch.py">
|
||||
<arg name="use_sim_time" value="$(arg use_sim_time)" />
|
||||
<arg name="map" value="$(arg map)" />
|
||||
</include>
|
||||
|
||||
<!-- RViz node -->
|
||||
<node pkg="rviz2" exec="rviz2" output="screen">
|
||||
<param name="config" value="$(find-pkg-share locker98_tools_bringup)/rviz/nav2_config.rviz" />
|
||||
</node>
|
||||
</launch>
|
||||
```
|
100
docs/General ROS 2/SLAM and Navigation/SLAM.md
Executable file
100
docs/General ROS 2/SLAM and Navigation/SLAM.md
Executable file
@ -0,0 +1,100 @@
|
||||
# SLAM
|
||||
## What is SLAM
|
||||
**SLAM** stands for **Simultaneous Localization and Mapping**. It is a computational problem in robotics and computer vision where a robot or device:
|
||||
1. **Localizes itself**: Determines its position and orientation within an environment.
|
||||
2. **Maps the environment**: Creates a map of its surroundings while navigating through it.
|
||||
|
||||
SLAM enables robots to operate autonomously in unknown environments by building a map and tracking their position on that map in real-time.
|
||||
|
||||
## Starting SLAM from the Terminal
|
||||
Here are the terminal commands for launching the SLAM toolkit.
|
||||
|
||||
```bash
|
||||
# Start robot or robot simulator in this case I wil use the turtlebot3
|
||||
ros2 launch turtlebot3_gazebo turtlebot3_world.launch.py
|
||||
|
||||
# Start nav2
|
||||
ros2 launch nav2_bringup navigation_launch.py
|
||||
# Start SLAM
|
||||
ros2 launch slam_toolbox online_async_launch.py
|
||||
# Launch rviz2 and add the TF visualization and the map visualization
|
||||
ros2 run rviz2 rviz2
|
||||
```
|
||||
|
||||
## Custom SLAM Launch File
|
||||
Here is a custom ROS 2 Launch file
|
||||
|
||||
=== "Python"
|
||||
|
||||
```python title="slam.launch.py" linenums="1"
|
||||
from launch import LaunchDescription
|
||||
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
|
||||
from launch_ros.actions import Node
|
||||
from ament_index_python.packages import get_package_share_directory
|
||||
from launch.launch_description_sources import PythonLaunchDescriptionSource
|
||||
from launch.substitutions import LaunchConfiguration
|
||||
import os
|
||||
|
||||
def generate_launch_description():
|
||||
# Declare arguments
|
||||
use_sim_time = LaunchConfiguration('use_sim_time', default='False')
|
||||
|
||||
# Get package share directories
|
||||
nav2_bringup_dir = get_package_share_directory('nav2_bringup')
|
||||
slam_toolbox_dir = get_package_share_directory('slam_toolbox')
|
||||
locker98_tools_bringup_dir = get_package_share_directory('locker98_tools_bringup')
|
||||
|
||||
# Include the navigation launch file
|
||||
navigation_launch = IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource(
|
||||
os.path.join(nav2_bringup_dir, 'launch', 'navigation_launch.py')
|
||||
),
|
||||
launch_arguments={'use_sim_time': use_sim_time}.items()
|
||||
)
|
||||
|
||||
# Include the SLAM toolbox launch file
|
||||
slam_launch = IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource(
|
||||
os.path.join(slam_toolbox_dir, 'launch', 'online_async_launch.py')
|
||||
),
|
||||
launch_arguments={'use_sim_time': use_sim_time}.items()
|
||||
)
|
||||
|
||||
# RViz2 node
|
||||
rviz2_node = Node(
|
||||
package='rviz2',
|
||||
executable='rviz2',
|
||||
output='screen',
|
||||
arguments=[
|
||||
'-d', os.path.join(locker98_tools_bringup_dir, 'rviz', 'slam_config.rviz')
|
||||
]
|
||||
)
|
||||
|
||||
return LaunchDescription([
|
||||
DeclareLaunchArgument('use_sim_time', default_value='False', description='Use simulation time'),
|
||||
navigation_launch,
|
||||
slam_launch,
|
||||
rviz2_node
|
||||
])
|
||||
```
|
||||
|
||||
=== "XML"
|
||||
|
||||
This is the XML version that is much easier to understand but for some reason it does not work. There is some error with the args the makes it error every time I try to build it.
|
||||
|
||||
```xml title="slam.launch.xml" linenums="1"
|
||||
<launch>
|
||||
<arg name="use_sim_time" default="False" />
|
||||
|
||||
<include file="$(find-pkg-share nav2_bringup)/launch/navigation_launch.py">
|
||||
<arg name="use_sim_time" value="$(arg use_sim_time)"/>
|
||||
</include>
|
||||
|
||||
<include file="$(find-pkg-share slam_toolbox)/launch/online_async_launch.py">
|
||||
<arg name="use_sim_time" value="$(arg use_sim_time)"/>
|
||||
</include>
|
||||
|
||||
<node pkg="rviz2" executable="rviz2" output="screen" args="-d $(find-pkg-share locker98_tools_bringup)/rviz/nav2_slam.rviz" />
|
||||
</launch>
|
||||
```
|
||||
|
@ -101,7 +101,7 @@ ros2 launch turtlebot4_viz view_robot.launch.py
|
||||
|
||||
Once you are done creating the map make sure you save it.
|
||||
```bash
|
||||
ros2 run nav2_map_server map_saver_cli -f "map_name"
|
||||
ros2 run nav2_map_server map_saver_cli -f folder/to/save/map_name
|
||||
```
|
||||
|
||||
|
||||
|
@ -1,5 +1,5 @@
|
||||
# Welcome
|
||||
Welcome this is the documenation for the Rhodes State ROS 2 Robotics equitment. This information is a collection of useful tips gathered from [Clearpath Robot Docs](https://docs.clearpathrobotics.com/docs/robots/), [Clearpath ROS 2](https://docs.clearpathrobotics.com/docs/ros/), and [Turtlebot 4 Manuel](https://turtlebot.github.io/turtlebot4-user-manual/). It also has informtation from the following courses; [ROS2 For Beginners](https://www.udemy.com/course/ros2-for-beginners)
|
||||
Welcome this is the documenation for ROS 2. This information is a collection of useful tips gathered from [Clearpath Robot Docs](https://docs.clearpathrobotics.com/docs/robots/), [Clearpath ROS 2](https://docs.clearpathrobotics.com/docs/ros/), and [Turtlebot 4 Manuel](https://turtlebot.github.io/turtlebot4-user-manual/). It also has informtation from the following courses; [ROS2 For Beginners](https://www.udemy.com/course/ros2-for-beginners), [ROS2 for Beginners Level 2 - TF | URDF | RViz | Gazebo](https://www.udemy.com/course/ros2-tf-urdf-rviz-gazebo), and [ROS2 Nav2 [Navigation 2 Stack] - with SLAM and Navigation](https://www.udemy.com/course/ros2-nav2-stack)
|
||||
|
||||
# General ROS 2
|
||||
This section covers general topics and tools that are useful for ROS 2 development.
|
||||
|
Loading…
Reference in New Issue
Block a user