reactive_move 3.9 KB
Newer Older
1
#!/usr/bin/python3
2 3 4
"""Basic control of the robot, move forward and avoid obstacles. Doesn't get stuck"""

# imports
5
import rclpy
6
import math as m
7 8 9 10
from rclpy.node import Node
from sensor_msgs.msg import PointCloud2
from geometry_msgs.msg import Twist
import sensor_msgs_py.point_cloud2
11
import time
12

13
# main class
14
class ReactiveMove(Node):
15

16 17 18
    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
19 20
    RECT_WIDTH = 0.5
    RECT_LENGTH = 0.5
21 22

    # Robot velocities
23 24
    ANGULAR_VELOCITY = 1.0
    LINEAR_VELOCITY = 0.2
25
    
26
    def __init__(self, name="reactive_move", timerFreq = 1/60.0):
27 28
        """ constructor """
        super().__init__(name) #  Create the node
29

30 31
        # Initialize a subscriber
        self.create_subscription(PointCloud2, 'scan_points', self.scan_callback, 10)
32

33 34
        # Initialize a publisher
        self._velocity_publisher = self.create_publisher(Twist, 'cmd_vel', 10)
35

36 37 38 39 40 41 42 43
        # Initialize a clock for the publisher
        self.create_timer(timerFreq, self.publish_velo)

        # Initialize variables
        self._timerFreq = timerFreq
        self._previousScanTime = None
        self._previousStraightMvtTime = None
        self._points = []
44

45

46 47

    def scan_callback(self, scanMsg):
48
        """
49
        Save received points for future calculations
50
        """
51
        self._points = sensor_msgs_py.point_cloud2.read_points(scanMsg)
52

53
        self._previousScanTime = time.time()
54

55 56 57
    
    def calcul_velo(self):
        """
58
        Calculate the velocity based on the lidar detected points and other data
59 60 61 62 63 64 65 66 67
        """

        now = time.time()


        # If scan data received more than 1s ago, stop the robot
        if now - self._previousScanTime > 1: 
            print("STOP ROBOT")
            return Twist()  # Return a zero velocity
68
        
69 70
        # 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°
71 72 73 74 75 76 77 78 79
        if self._previousStraightMvtTime and self.MAX_STUCK_TIME < now - self._previousStraightMvtTime <= self.MAX_STUCK_TIME + m.pi: 
            velo = Twist()
            velo.angular.z = self.ANGULAR_VELOCITY
            print("U-TURN")
            return velo

        # Default case
        x, y = firstPointInFront(self._points, self.RECT_LENGTH, self.RECT_WIDTH / 2.0)
        velocity = Twist()
80 81
        if x and y:
            if y >= 0:  # Point is in the left part of the rectangle -> Turn right
82 83
                velocity.angular.z = -self.ANGULAR_VELOCITY
                print("TURN RIGHT")
84
            else:  # Point is in the right part of the rectangle -> Turn left
85 86 87
                velocity.angular.z = self.ANGULAR_VELOCITY
                print("TURN LEFT")
            
88
        else:  # If there's not point in front, go straight
89 90 91 92 93 94 95 96 97 98
            velocity.linear.x = self.LINEAR_VELOCITY
            self._previousStraightMvtTime = now
            print("STRAIGHT")

        return velocity





99

100 101 102 103 104
    def publish_velo(self):
        """ 
        Publish velocity independently of the callback
        """

105 106 107 108 109 110
        # Make sure at least one callback is made
        if not self._previousScanTime:
            return -1


        velocity = self.calcul_velo()
111

112
        self._velocity_publisher.publish(velocity) #  Move according to previously calculated velocity
113 114

        return 0
115 116


117
# Static functions
118
def firstPointInFront(points:list, maxX, maxY):
119 120 121
    """
    Check if points in front of the robot (in the rectangle with forward distance maxX and lateral distance of 2*maxY)
    """
122 123 124 125 126 127 128
    for (x,y,_) in points:
        if(x>0 and x < maxX and abs(y) < maxY):
            return (x,y)
    
    return (None, None)


129
# Main loop
130
def main():
131 132 133
    """
    Main loop
    """
134
    rclpy.init()
135 136
    rosNode = ReactiveMove()
    rclpy.spin(rosNode)
137 138


139
    rosNode.destroy_node()
140 141 142 143
    rclpy.shutdown()

if __name__ == "__main__":
    main()