-
Notifications
You must be signed in to change notification settings - Fork 7
Using ROS from Python code [2425]
On VSCode, open the file RBT1001/src/week1/turtles_controller.py
. This is a template that is already pre-filled with some definitions and statements to make it easier to write your first ROS node.
A python ROS should start with a main function, such as:
def main(args=None):
rclpy.init(args=args)
turtles_controller = TurtlesController()
rclpy.spin(turtles_controller)
turtles_controller.destroy_node()
rclpy.shutdown()
where rclpy.spin()
is a blocking function that starts the node and waits until it terminates.
The node itself, is a class that inherits the Node
object:
class TurtlesController(Node):
def __init__(self):
# Defines the name of the node
super().__init__('turtles_controller')
...
turtlesim
node is running - if not, relaunch it.
:arrow_forward: :desktop_computer: From a terminal, navigate to the location of the script (e.g. cd src/week1
) and launch the script:
python3 turtles_controller.py
turtles_controller
node in the ROS network - try it!
from geometry_msgs.msg import Twist
class TurtlesController(Node):
def __init__(self):
...
self.t1_cmd_pub = self.create_publisher(
Twist,
'/turtle1/cmd_vel',
10
)
create_publisher
declares that the node publishes messages of type Twist
(imported from the geometry_msgs.msg
module), over a topic named /turtle1/cmd_vel
, and that the “queue size” is 10. Queue size is a required QoS (quality of service) setting that limits the amount of queued messages if a subscriber is not receiving them fast enough.
To publish a message, we need to create a Twist
message object first and then call the publisher's publish()
function. For example:
...
msg = Twist()
msg.angular.z = 0.7 * self.t1_rot_direction
self.t1_cmd_pub.publish(msg)
...
In a similar way, subscribing to receive a topic's messages can be done by calling the create_subscription
method. This time, we also need to pass a callback function, called t1_pose_cb
in the example below, which receives the messages.
class TurtlesController(Node):
def __init__(self):
...
self.t1_pose_sub = self.create_subscription(
Pose,
"/turtle1/pose",
self.t1_pose_cb,
10
)
...
def t1_pose_cb(self, msg):
self.get_logger().debug('I got turtle1 pose: "%s"' % msg)
self.t1_pose = msg
If you open the script RBT1001/src/week1/random_arm_controller.py
, you will find a template ready for you.
## TODO
in the code and complete as instructed to achieve the objective.
mecharm
node is running, close the Joint State Publisher window from the graphical interface (otherwise it will override the joint_state
messages of your code) and launch your random_arm_controller
!
Parts for the workshops are extracted, edited from and/or inspired by the following sources.
- Official ROS humble tutorials: https://docs.ros.org/en/humble/Tutorials.html
- Elephant Robotics docs: https://docs.elephantrobotics.com/docs/gitbook-en/