...
 
Commits (4)
# group Astro, repository for the UV LARM
---
## Authors :
Inès El Hadri
# Astro Group's repository for the LARM UV
## Authors
Inès El Hadri
Lucas Naury
---
---
## Introduction
This repository is a ROS2 package that allows the control of a kobuki robot.
### Table of Contents :
1. [Authors](#authors)
1. [Introduction](#introduction)
1. [How it works](#how-it-works)
1. [Goal](#goal)
1. [Expected behaviour](#expected-behaviour)
1. [Additional functionality](#additional-functionality)
1. [Installation](#installation)
1. [Requirements](#requirements)
1. [Install the package](#install-the-package)
1. [Tune the camera HSV](#tune-the-camera-hsv)
1. [Build the package](#build-the-packages)
1. [How to use the package](#how-to-use-the-package)
1. [In simulation](#in-simulation)
......@@ -21,11 +28,46 @@ This repository is a ROS2 package that allows the control of a kobuki robot.
1. [Visualization](#visualization)
1. [Frequently Asked Questions](#faq)
---
## How it works
### Goal
The goal is to explore a closed area (i.e. an area bounded with obstacles) with the robot while avoiding obstacles. While doing so, we must determine the number and position of green painted bottles.
### Expected behaviour
- The robot moves **continuously** in the area by **avoiding obstacles**
- If there are no obstacles, it moves straight
- If an obstacle is in front, it turns the opposite direction until there's no obstacle left in front.
- Using the **SLAM algorithm** with data from the LiDAR and the odometer, the robot builds a map and localizes itself in it.
- Using a RealSense RGBD camera (D435i), the robot is able to **detect the green bottles**. Messages are sent in topics:
- `detection` : to state the detection
- `bottle_relative_pos` : to tell the position of the bottle relative to the camera
- `bottle_marker` : to mark the position of a bottle on the map
- Experiments can be performed with **2 computers**:
- one on the robot (Control PC) running all the robot, movement and vision nodes
- a second for visualization and human control (Operator PC)
### Additional functionality
- An [**automatic HSV tuner script**](#tune-the-camera-hsv) allows you to calculate the ideal threshold to mask your bottle
- Most configuration variables (robot speeds, bounding boxes, are set as **ROS parameters** so that they can be modified
- The robot stops moving when you press any of the **3 robot buttons**. If you press it again, movement will continue.
> All other data is still being processed when the robot is in pause
- The robot **stops when you lift it** (i.e. the wheels are "falling"). It you put the robot back on the ground, movement will continue.
In this branch, you'll also find a node that **automates the map discovery** (by sending goal poses to unknown areas for the robot to go to).
> This has only been tested on the simulator, since we didn't have time to test it on the real robot
## Installation
### Requirements
Before starting, please ensure you have installed the following
- ROS2 Iron : https://docs.ros.org/en/iron/index.html
- ROS2 packages : `apt install ros-iron-slam-toolbox ros-iron-nav2-bringup`
- Python 3.10 : https://www.python.org/downloads/
- Python packages :
* math, os, signal, sys, time (installed with python)
......@@ -36,10 +78,11 @@ Before starting, please ensure you have installed the following
* cvbridge3
* scikit-image
</br>
>Command :
>`pip install numpy colcon-common-extensions opencv-python pyrealsense2 cvbridge3 scikit-image`
- $`\textcolor{red}{\text{[OPTIONAL]}}`$ Gazebo (for the simulation)
> Command :
> `pip install numpy colcon-common-extensions opencv-python pyrealsense2 cvbridge3 scikit-image`
- $`\textcolor{red}{\text{[OPTIONAL]}}`$ Gazebo (for the simulation) (`apt install ros-iron-gazebo-ros-pkgs`)
- $`\textcolor{red}{\text{[OPTIONAL]}}`$ Teleop twist keyboard (to control manually the robot)
### Configuration
......@@ -55,18 +98,20 @@ export ROS_AUTOMATIC_DISCOVERY_RANGE=LOCALHOST #Tell ROS to make your nodes only
However, if you want to be able to visualize data from another computer on the same network, add :
```
export ROS_AUTOMATIC_DISCOVERY_RANGE=SUBNET #Tell ROS to make your nodes only accessible by the same machine
export ROS_AUTOMATIC_DISCOVERY_RANGE=SUBNET #Tell ROS to make your nodes accessible by machines on the same network
```
### Install the package
1. Open the command prompt in the ROS2 workspace directory
1. Clone the IMT Tbot packages : `git clone https://bitbucket.org/imt-mobisyst/pkg-tbot/src/master/`
1. Clone the IMT Tbot packages : `git clone https://bitbucket.org/imt-mobisyst/pkg-tbot.git` and `git clone https://bitbucket.org/imt-mobisyst/pkg-tsim.git`
1. Clone this repository : `git clone http://gvipers.imt-nord-europe.fr/ines.el.hadri/larm.git`
### Tune the camera HSV
To tune the HSV threshold parameters for the camera mask, we will use a script to automate it.
First, put a bottle in front of the robot.
Then, go in the `larm` directory and launch the HSV tuner python script using the following command
......@@ -83,7 +128,7 @@ A window will popup with a frame from the RealSense camera :
### Build the packages
In the same ROS2 workspace directory:
- `./master/bin/install`
- `./pkg-tbot/bin/install`
- `colcon build`
- `source install/setup.sh`
......@@ -97,18 +142,27 @@ First, go in the ROS2 workspace.
To launch the challenge 1 in **simulation**, run the following command :
`ros2 launch grp_astro simulation_launch.yaml`
If you want to launch the **automatic discovery nodes**, run the following command instead :
`ros2 launch grp_astro auto_simulation_launch.yaml`
### On the tbot
To launch the challenge 1 on the **real turtlebot**, run the following command :
`ros2 launch grp_astro tbot_launch.yaml`
### Visualization
In parallel, if you want to **visualize** the information that is published on the different topics, you can run
`ros2 launch grp_astro visualize.launch.py`
In parallel, if you want to **visualize** the information that is published on the different topics, you can run :
- `ros2 launch tbot_operator_launch.yaml` for the real robot
- `ros2 launch sim_operator_launch.yaml` in simulation
> If you want to run this visualization on another computer than the one running the robot, make sure :
> - they are on the **same network**
> - they have the same **`ROS_DOMAIN_ID`** environment variable
> - they have configured **`ROS_AUTOMATIC_DISCOVERY_RANGE=SUBNET`** in the environment variables
If you want to launch the **automatic discovery visualizer** (path found, goal poses...), run the following commands instead :
- `ros2 launch auto_sim_operator_launch.yaml` in simulation
---
## FAQ
......@@ -55,6 +55,7 @@ install( PROGRAMS
src/reactive_move
src/scan2point_cloud
src/bottle_mapping
src/auto_discovery
DESTINATION lib/${PROJECT_NAME}
)
\ No newline at end of file
Panels:
- Class: rviz_common/Displays
Help Height: 70
Name: Displays
Property Tree Widget:
Expanded:
- /Global Options1
- /Status1
- /TF1/Frames1
Splitter Ratio: 0.5
Tree Height: 727
- Class: rviz_common/Selection
Name: Selection
- Class: rviz_common/Tool Properties
Expanded:
- /2D Goal Pose1
- /Publish Point1
Name: Tool Properties
Splitter Ratio: 0.5886790156364441
- Class: rviz_common/Views
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
- Class: rviz_common/Time
Experimental: false
Name: Time
SyncMode: 0
SyncSource: ""
Visualization Manager:
Class: ""
Displays:
- Alpha: 0.5
Cell Size: 1
Class: rviz_default_plugins/Grid
Color: 160; 160; 164
Enabled: true
Line Style:
Line Width: 0.029999999329447746
Value: Lines
Name: Grid
Normal Cell Count: 0
Offset:
X: 0
Y: 0
Z: 0
Plane: XY
Plane Cell Count: 10
Reference Frame: <Fixed Frame>
Value: true
- Alpha: 0.699999988079071
Binary representation: false
Binary threshold: 100
Class: rviz_default_plugins/Map
Color Scheme: map
Draw Behind: false
Enabled: true
Name: Map
Topic:
Depth: 5
Durability Policy: Volatile
Filter size: 10
History Policy: Keep Last
Reliability Policy: Reliable
Value: /map
Update Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /map_updates
Use Timestamp: false
Value: true
- Class: rviz_default_plugins/TF
Enabled: true
Frame Timeout: 15
Frames:
All Enabled: false
base_footprint:
Value: false
base_link:
Value: true
camera_link:
Value: false
caster_back_link:
Value: false
caster_front_link:
Value: false
cliff_sensor_front_link:
Value: false
cliff_sensor_left_link:
Value: false
cliff_sensor_right_link:
Value: false
imu_link:
Value: false
laser_link:
Value: false
left_wheel:
Value: false
map:
Value: false
odom:
Value: false
right_wheel:
Value: false
Marker Scale: 1
Name: TF
Show Arrows: true
Show Axes: true
Show Names: false
Tree:
map:
odom:
base_footprint:
base_link:
camera_link:
{}
caster_back_link:
{}
caster_front_link:
{}
cliff_sensor_front_link:
{}
cliff_sensor_left_link:
{}
cliff_sensor_right_link:
{}
imu_link:
{}
laser_link:
{}
left_wheel:
{}
right_wheel:
{}
Update Interval: 0
Value: true
- Class: rviz_default_plugins/MarkerArray
Enabled: true
Name: MarkerArray
Namespaces:
slam_toolbox: true
slam_toolbox_edges: true
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /slam_toolbox/graph_visualization
Value: true
- Alpha: 1
Axes Length: 1
Axes Radius: 0.10000000149011612
Class: rviz_default_plugins/Pose
Color: 255; 25; 0
Enabled: true
Head Length: 0.30000001192092896
Head Radius: 0.10000000149011612
Name: Pose
Shaft Length: 1
Shaft Radius: 0.05000000074505806
Shape: Arrow
Topic:
Depth: 5
Durability Policy: Volatile
Filter size: 10
History Policy: Keep Last
Reliability Policy: Reliable
Value: /goal_pose
Value: true
- Alpha: 1
Buffer Length: 1
Class: rviz_default_plugins/Path
Color: 25; 255; 0
Enabled: true
Head Diameter: 0.30000001192092896
Head Length: 0.20000000298023224
Length: 0.30000001192092896
Line Style: Lines
Line Width: 0.029999999329447746
Name: Path
Offset:
X: 0
Y: 0
Z: 0
Pose Color: 255; 85; 255
Pose Style: None
Radius: 0.029999999329447746
Shaft Diameter: 0.10000000149011612
Shaft Length: 0.10000000149011612
Topic:
Depth: 5
Durability Policy: Volatile
Filter size: 10
History Policy: Keep Last
Reliability Policy: Reliable
Value: /transformed_global_plan
Value: true
Enabled: true
Global Options:
Background Color: 48; 48; 48
Fixed Frame: map
Frame Rate: 30
Name: root
Tools:
- Class: rviz_default_plugins/Interact
Hide Inactive Objects: true
- Class: rviz_default_plugins/MoveCamera
- Class: rviz_default_plugins/Select
- Class: rviz_default_plugins/FocusCamera
- Class: rviz_default_plugins/Measure
Line color: 128; 128; 0
- Class: rviz_default_plugins/SetInitialPose
Covariance x: 0.25
Covariance y: 0.25
Covariance yaw: 0.06853891909122467
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /initialpose
- Class: rviz_default_plugins/SetGoal
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /goal_pose
- Class: rviz_default_plugins/PublishPoint
Single click: true
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /clicked_point
Transformation:
Current:
Class: rviz_default_plugins/TF
Value: true
Views:
Current:
Angle: -0.004999999888241291
Class: rviz_default_plugins/TopDownOrtho
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Scale: 42.38160705566406
Target Frame: <Fixed Frame>
Value: TopDownOrtho (rviz_default_plugins)
X: -0.4481850564479828
Y: 1.6712069511413574
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 1016
Hide Left Dock: false
Hide Right Dock: false
QMainWindow State: 000000ff00000000fd0000000400000000000001840000035afc020000000efb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d0000035a000000c900fffffffb0000000a0049006d0061006700650000000152000000ca0000000000000000fb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d00610067006500000001ab000000850000000000000000fb0000000a0049006d00610067006500000001f2000001a00000000000000000fb0000000a0049006d006100670065010000012d000000ef0000000000000000fb0000000a0049006d0061006700650100000222000000e80000000000000000fb0000000a0049006d0061006700650100000310000000820000000000000000000000010000010f0000035afc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d0000035a000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073a0000003efc0100000002fb0000000800540069006d006501000000000000073a000002fb00fffffffb0000000800540069006d006501000000000000045000000000000000000000049b0000035a00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: false
Width: 1850
X: 70
Y: 27
launch:
# Launch rviz2
- node:
pkg: "rviz2"
exec: "rviz2"
name: "rviz2"
args: "-d $(find-pkg-share grp_astro)/config/auto.rviz"
# Launch a terminal that listens to the "detection" topic to print when we see a bottle in the FOV
- executable:
cmd: gnome-terminal --tab -e 'ros2 topic echo "detection"'
# Launch teleop
- executable:
cmd: gnome-terminal --tab -e 'ros2 run teleop_twist_keyboard teleop_twist_keyboard --ros-args --remap cmd_vel:=/multi/cmd_teleop'
launch:
# Include the challenge 1 simulation launch file
- include:
file: "$(find-pkg-share tbot_sim)/launch/challenge-1.launch.py"
# Launch a SLAM algorithm
- include:
file: "$(find-pkg-share slam_toolbox)/launch/online_sync_launch.py"
# Go to goal points
- include:
file: "$(find-pkg-share nav2_bringup)/launch/navigation_launch.py"
# Send goal points
- node:
pkg: "grp_astro"
exec: "auto_discovery"
name: "auto_discovery"
\ No newline at end of file
#!/usr/bin/python3
# Imports
import rclpy
from rclpy.node import Node
from geometry_msgs.msg import PoseStamped, Twist, Pose
from nav_msgs.msg import OccupancyGrid
from nav_msgs.msg import Odometry
from tf2_ros.transform_listener import TransformListener
from tf2_ros.buffer import Buffer
from random import random, sample
import math as m, numpy as np
# Class
class AutoDisco(Node):
def __init__(self, name="auto_disco", timerFreq=1.0/60):
super().__init__(name)
# Initialiaze subscribers / publishers
self.init_publishers(timerFreq)
self.init_subscribers()
# Node variables
self._robot_speed = Twist()
self._map = None
self._canPublishGoal = True
self._robotPose = None
# Transform frames
self._tf_buffer = Buffer()
self._tf_listener = TransformListener(self._tf_buffer, self)
def init_publishers(self, timerFreq):
self._goal_publisher = self.create_publisher(PoseStamped, 'goal_pose', 10)
self.create_timer(timerFreq, self.loop)
def init_subscribers(self):
self.create_subscription(Twist, '/cmd_vel', self.speed_callback, 10)
self.create_subscription(OccupancyGrid, '/map', self.map_callback, 10)
self.create_subscription(Odometry, '/odom', self.odom_callback, 10)
def speed_callback(self, msg):
"""
Get robot speed
"""
self._robot_speed = msg
def map_callback(self, msg):
"""
Get map data
"""
self._map = msg
def odom_callback(self, odom):
"""
Get robot pose on the map, thanks to SLAM
"""
self._robotPose = odom.pose.pose
def loop(self):
# Map view
if self._map is None or self._robotPose is None:
return
if self._robot_speed != Twist():
self._canPublishGoal = True
elif self._canPublishGoal:
pose = PoseStamped()
# Get map settings
resolution = self._map.info.resolution
width = self._map.info.width
height = self._map.info.height
origin_position = self._map.info.origin.position
data = self._map.data
# Save unknown points' coordinates
values = []
for x in range(width):
for y in range(height):
if data[x+y*width] == -1:
values.append((x, y))
# Define a distance to check around the robot
xDist = int(0.5 / resolution) # 50cm in px
yDist = int(0.5 / resolution) # 50cm in px
# Filter the points to only get the ones without any neighbours in a square around them
filteredValues = [(x,y) for x,y in values if x>xDist and x < width - xDist and y>yDist and y<height-yDist]
pointsWithoutNeighbour = []
for x,y in filteredValues:
hasKnownNeighbour = False
for xOffset in range(-xDist, xDist+1):
for yOffset in range(-yDist, yDist+1):
if data[(x + xOffset) + (y + yOffset)*width] != -1:
hasKnownNeighbour = True
break
if hasKnownNeighbour:
break
if not hasKnownNeighbour:
pointsWithoutNeighbour.append((x,y))
# Get robot position in map
trans = self._tf_buffer.lookup_transform("map", "odom", rclpy.time.Time())
robotX = trans.transform.translation.x
robotY = trans.transform.translation.y
yaw = self.quaternionToYaw(trans.transform.rotation)
robotX += self._robotPose.position.x * m.cos(yaw) - self._robotPose.position.y * m.sin(yaw)
robotY += self._robotPose.position.x * m.sin(yaw) + self._robotPose.position.y * m.cos(yaw)
# Order all the points without neighbours by distance relative to the robot
pointsWithoutNeighbour = [(x, y, (x*resolution + origin_position.x - robotX)**2 + (y*resolution + origin_position.y - robotY)**2) for x, y in pointsWithoutNeighbour]
pointsWithoutNeighbour.sort(key = lambda x: x[2])
# If there is at least one point without neighbour, go to the closest one
if len(pointsWithoutNeighbour) > 0:
x,y,_ = pointsWithoutNeighbour[0]
# Otherwise if there are still unknown points, pick one of them at random
elif len(values) > 0:
x,y = sample(values, 1)[0]
# If all the map is known, go to a random point
else:
x,y = int(random()*width), int(random()*height)
# Transform the map coordinates into real world coordinates
pose.pose.position.x = x * resolution + origin_position.x
pose.pose.position.y = y * resolution + origin_position.y
pose.header.frame_id = "map"
pose.header.stamp = self.get_clock().now().to_msg()
# Publish goal pose
self._goal_publisher.publish(pose)
self._canPublishGoal = False
def quaternionToYaw(self, q):
# Convert quaternion to yaw
x = q.x
y = q.y
z = q.z
w = q.w
siny_cosp = 2 * (w * z + x * y)
cosy_cosp = 1 - 2 * (y * y + z * z)
yaw = np.arctan2(siny_cosp, cosy_cosp)
return yaw
def main():
"""
Main loop
"""
rclpy.init()
rosNode = AutoDisco()
rclpy.spin(rosNode)
rosNode.destroy_node()
rclpy.shutdown()
if __name__ == "__main__":
main()
\ No newline at end of file