tuto_move 1.08 KB
Newer Older
1
#!/usr/bin/python3
2 3 4 5 6 7 8 9 10 11 12 13
import rclpy                  # core ROS2 client python librairie
from rclpy.node import Node   # To manipulate ROS Nodes

from geometry_msgs.msg import Twist # Message to publish:

print("tuto_move :: START...")

def main():
    rclpy.init()     # Initialize ROS2 client
    myNode= Node('move_node') # Create a Node, with a name     

    # Initialize a publisher:
14
    velocity_publisher = myNode.create_publisher(Twist, '/cmd_vel', 10)
15 16 17 18 19 20 21 22 23 24 25 26 27


    # Start the ros infinit loop with myNode.
    while True :
        rclpy.spin_once( myNode, timeout_sec=0.1 )
        print("Running...")

        # Publish a msg
        velo = Twist()
        velo.linear.x= 0.2   # meter per second
        velo.angular.z = 0.5 # radians per second
        velocity_publisher.publish(velo)    

28 29
    # At the end, destroy the node explicitly.
    myNode.destroy_node()
30

31 32
    # and shut the light down.
    rclpy.shutdown()
33

34
    print("tuto_move :: STOP.")
35 36 37 38 39 40 41 42



# activate main() function,
# if the file is executed as a script (ie. not imported).
if __name__ == '__main__':
    # call main() function
    main()