Commit c28eadac authored by Inès EL HADRI's avatar Inès EL HADRI 💤

reorganization of the files

parent e2c7ee26
...@@ -3,10 +3,5 @@ launch: ...@@ -3,10 +3,5 @@ launch:
- include: - include:
file: "$(find-pkg-share tuto_kickoff)/launch/include/tuto_reel.yaml" file: "$(find-pkg-share tuto_kickoff)/launch/include/tuto_reel.yaml"
# - node:
# pkg: "teleop_twist_keyboard"
# exec: "teleop_twist_keyboard"
# name: "teleop"
- executable: - executable:
cmd: gnome-terminal --tab -e 'ros2 run teleop_twist_keyboard teleop_twist_keyboard --ros-args --remap turtle1/cmd_vel:=/multi/cmd_nav' cmd: gnome-terminal --tab -e 'ros2 run teleop_twist_keyboard teleop_twist_keyboard --ros-args --remap turtle1/cmd_vel:=/multi/cmd_nav'
...@@ -3,10 +3,5 @@ launch: ...@@ -3,10 +3,5 @@ launch:
- include: - include:
file: "$(find-pkg-share tuto_kickoff)/launch/include/tuto_sim.yaml" file: "$(find-pkg-share tuto_kickoff)/launch/include/tuto_sim.yaml"
# - node:
# pkg: "teleop_twist_keyboard"
# exec: "teleop_twist_keyboard"
# name: "teleop"
- executable: - executable:
cmd: gnome-terminal --tab -e 'ros2 run teleop_twist_keyboard teleop_twist_keyboard --ros-args --remap turtle1/cmd_vel:=/cmd_vel' cmd: gnome-terminal --tab -e 'ros2 run teleop_twist_keyboard teleop_twist_keyboard --ros-args --remap turtle1/cmd_vel:=/cmd_vel'
#!/usr/bin/python3 #!/usr/bin/python3
"""Base node, does nothing."""
import rclpy # core ROS2 client python library import rclpy # core ROS2 client python library
from rclpy.node import Node # To manipulate ROS Nodes from rclpy.node import Node # To manipulate ROS Nodes
......
#!/usr/bin/python3 #!/usr/bin/python3
"""Basic control of the robot, move forward and avoid obstacles. Doesn't get stuck"""
# imports
import rclpy import rclpy
import math as m import math as m
from rclpy.node import Node from rclpy.node import Node
...@@ -7,16 +10,22 @@ from geometry_msgs.msg import Twist ...@@ -7,16 +10,22 @@ from geometry_msgs.msg import Twist
import sensor_msgs_py.point_cloud2 import sensor_msgs_py.point_cloud2
import time import time
# main class
class ReactiveMove(Node): class ReactiveMove(Node):
MAX_STUCK_TIME = 5 # Time before the robot is considered to be stuck and has to make a U-turn MAX_STUCK_TIME = 5 # Time before the robot is considered to be stuck and has to make a U-turn
# Rectangle of vision of the robot
RECT_WIDTH = 0.5 RECT_WIDTH = 0.5
RECT_LENGTH = 0.5 RECT_LENGTH = 0.5
# Robot velocities
ANGULAR_VELOCITY = 1.0 ANGULAR_VELOCITY = 1.0
LINEAR_VELOCITY = 0.2 LINEAR_VELOCITY = 0.2
def __init__(self, name="reactive_move", timerFreq = 1/60.0): def __init__(self, name="reactive_move", timerFreq = 1/60.0):
super().__init__(name) # Create the node """ constructor """
super().__init__(name) # Create the node
# Initialize a subscriber # Initialize a subscriber
self.create_subscription(PointCloud2, 'scan_points', self.scan_callback, 10) self.create_subscription(PointCloud2, 'scan_points', self.scan_callback, 10)
...@@ -46,7 +55,7 @@ class ReactiveMove(Node): ...@@ -46,7 +55,7 @@ class ReactiveMove(Node):
def calcul_velo(self): def calcul_velo(self):
""" """
Calculate the velocity based on the "map" points and other data Calculate the velocity based on the lidar detected points and other data
""" """
now = time.time() now = time.time()
...@@ -57,7 +66,8 @@ class ReactiveMove(Node): ...@@ -57,7 +66,8 @@ class ReactiveMove(Node):
print("STOP ROBOT") print("STOP ROBOT")
return Twist() # Return a zero velocity return Twist() # Return a zero velocity
# If it's been rotating for more than 5s, it's probably stuck in a corner, so we rotate it completely, until >3.14s which is equivalent to a rotation of >180° # If it's been rotating for more than 5s, it's probably stuck in a corner
# In this case, a u-turn is performed, until >3.14s which is equivalent to a rotation of >180°
if self._previousStraightMvtTime and self.MAX_STUCK_TIME < now - self._previousStraightMvtTime <= self.MAX_STUCK_TIME + m.pi: if self._previousStraightMvtTime and self.MAX_STUCK_TIME < now - self._previousStraightMvtTime <= self.MAX_STUCK_TIME + m.pi:
velo = Twist() velo = Twist()
velo.angular.z = self.ANGULAR_VELOCITY velo.angular.z = self.ANGULAR_VELOCITY
...@@ -99,12 +109,12 @@ class ReactiveMove(Node): ...@@ -99,12 +109,12 @@ class ReactiveMove(Node):
velocity = self.calcul_velo() velocity = self.calcul_velo()
self._velocity_publisher.publish(velocity) # Move according to previously calculated velocity self._velocity_publisher.publish(velocity) Move according to previously calculated velocity
return 0 return 0
# Static functions
def firstPointInFront(points:list, maxX, maxY): def firstPointInFront(points:list, maxX, maxY):
""" """
Check if points in front of the robot (in the rectangle with forward distance maxX and lateral distance of 2*maxY) Check if points in front of the robot (in the rectangle with forward distance maxX and lateral distance of 2*maxY)
...@@ -116,7 +126,7 @@ def firstPointInFront(points:list, maxX, maxY): ...@@ -116,7 +126,7 @@ def firstPointInFront(points:list, maxX, maxY):
return (None, None) return (None, None)
# Main loop
def main(): def main():
""" """
Main loop Main loop
......
#!/usr/bin/python3 #!/usr/bin/python3
import rclpy # core ROS2 client python librairie """Move in cirle"""
from rclpy.node import Node # To manipulate ROS Nodes
from geometry_msgs.msg import Twist # Message to publish: # Imports
import rclpy # core ROS2 client python library
from rclpy.node import Node # Manipulate ROS Nodes
from geometry_msgs.msg import Twist
# Message to publish:
print("tuto_move :: START...") print("tuto_move :: START...")
# Main loop
def main(): def main():
"""Main loop"""
rclpy.init() # Initialize ROS2 client rclpy.init() # Initialize ROS2 client
myNode= Node('move_node') # Create a Node, with a name myNode= Node('move_node') # Create a Node, with a name
...@@ -14,7 +21,7 @@ def main(): ...@@ -14,7 +21,7 @@ def main():
velocity_publisher = myNode.create_publisher(Twist, '/cmd_vel', 10) velocity_publisher = myNode.create_publisher(Twist, '/cmd_vel', 10)
# Start the ros infinit loop with myNode. # Start the ros infinite loop with myNode.
while True : while True :
rclpy.spin_once( myNode, timeout_sec=0.1 ) rclpy.spin_once( myNode, timeout_sec=0.1 )
print("Running...") print("Running...")
...@@ -35,8 +42,7 @@ def main(): ...@@ -35,8 +42,7 @@ def main():
# activate main() function, # activate main() function only if the file is executed as a script (ie. not imported).
# if the file is executed as a script (ie. not imported).
if __name__ == '__main__': if __name__ == '__main__':
# call main() function # call main() function
main() main()
\ No newline at end of file
#!/usr/bin/python3 #!/usr/bin/python3
"""Change Lidar message into point cloud object"""
import rclpy import rclpy
import math import math
from rclpy.node import Node from rclpy.node import Node
...@@ -6,13 +7,16 @@ from sensor_msgs.msg import LaserScan, PointCloud2 ...@@ -6,13 +7,16 @@ from sensor_msgs.msg import LaserScan, PointCloud2
from sensor_msgs_py import point_cloud2 from sensor_msgs_py import point_cloud2
from std_msgs.msg import Header from std_msgs.msg import Header
# Create node
rosNode= None rosNode= None
def scan_callback(scanMsg): def scan_callback(scanMsg):
"""receive a lidar message and send a pointcloud message in topic"""
global rosNode global rosNode
obstacles = ranges_to_positions(scanMsg) obstacles = ranges_to_positions(scanMsg)
sample = [ [ round(p[0], 2), round(p[1], 2), round(p[2], 2) ] for p in obstacles[10:20] ]
# Sample for the tuto :
sample = [ [ round(p[0], 2), round(p[1], 2), round(p[2], 2) ] for p in obstacles[10:20] ]
# rosNode.get_logger().info( f"\nheader:\n{scanMsg.header}\nnumber of ranges: {len(scanMsg.ranges)}\nSample: {sample}\n" ) # rosNode.get_logger().info( f"\nheader:\n{scanMsg.header}\nnumber of ranges: {len(scanMsg.ranges)}\nSample: {sample}\n" )
# Publish a msg # Publish a msg
...@@ -21,6 +25,7 @@ def scan_callback(scanMsg): ...@@ -21,6 +25,7 @@ def scan_callback(scanMsg):
def ranges_to_positions(scan_message: LaserScan) -> list: def ranges_to_positions(scan_message: LaserScan) -> list:
"""change a lidar message into a pointcloud message"""
obstacles= [] obstacles= []
angle= scan_message.angle_min angle= scan_message.angle_min
for aDistance in scan_message.ranges : for aDistance in scan_message.ranges :
...@@ -46,7 +51,5 @@ while True : ...@@ -46,7 +51,5 @@ while True :
rclpy.spin_once( rosNode ) rclpy.spin_once( rosNode )
rosNode.destroy_node() rosNode.destroy_node()
rclpy.shutdown() rclpy.shutdown()
\ No newline at end of file
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment