Tutorial 1: Starting the competition
This tutorial details the steps necessary to start the competition from a competitor package.
Starting the environment for Tutorial 1
To start the environment, use this command:
ros2 launch ariac_gazebo ariac.launch.py competitor_pkg:=ariac_tutorials trial_name:=tutorial dev_mode:=True
Running tutorial 1
To start tutorial 1, open a new terminal and use this command:
ros2 launch ariac_tutorials tutorial.launch.py tutorial:=1
Expected output of tutorial 1
Code explanation for Tutorial 1
This is the node used for tutorial 1. The functions from competition_interface.py which are used are highlighted.
#!/usr/bin/env python3
import rclpy
import threading
from rclpy.executors import MultiThreadedExecutor
from ariac_tutorials.competition_interface import CompetitionInterface
from ariac_msgs.msg import CompetitionState
def main(args=None):
rclpy.init(args=args)
interface = CompetitionInterface(enable_moveit=False)
executor = MultiThreadedExecutor()
executor.add_node(interface)
spin_thread = threading.Thread(target=executor.spin)
spin_thread.start()
interface.start_competition()
while not interface.get_competition_state == CompetitionState.ORDER_ANNOUNCEMENTS_DONE:
pass
interface.end_competition()
spin_thread.join()
if __name__ == '__main__':
main()
First, an instance of the CompetitionInterface
is created with enable_moveit
set to False
, as moveit_py is not needed for this tutorial. Then, an executor is created containing an instance of CompetitionInterface
. After this, a thread is created to spin the executor. The competition is then started using the start_competition
method in CompetitionInterface
. This uses the /ariac/start_competition service to start the competition. The node then waits until the competition state is ORDER_ANNOUNCEMENTS_DONE
. Finally, the competition is ended using the /ariac/end_competition
service and the thread is joined with the main thread.