ROS Communication
This section shows the ROS topics and services that are used to communicate between the Competitor Control System (CCS) and the ARIAC system. The definition of each message and service type is also provided.
Competition Topics
Topic Name |
Message Definition |
Description |
---|---|---|
|
Orders that the CCS should submit |
|
|
Current state of the competition |
|
|
Part information in each bin at program start-up |
|
|
Parts that will come on the conveyor belt |
|
|
State of the AGV |
|
|
State of |
|
|
State of the conveyor (enabled, power) |
|
|
Health of the robots (enabled or disabled) |
|
|
Health of the sensors (enabled or disabled) |
|
|
Position and velocity of the human and the ceiling robot |
|
|
State of the assembly station |
Sensor Topics
Sensor Type |
Topic Name |
Message Definition |
---|---|---|
break_beam |
|
ariac_msgs/msg/BreakBeamStatus |
proximity |
|
|
laser_profiler |
|
|
lidar |
|
|
rgb_camera |
|
|
rgbd_camera |
|
|
basic_logical_camera |
|
|
advanced_logical_camera |
|
Services
Service Name |
Service Definition |
Description |
---|---|---|
|
Start the competition |
|
|
End the competition |
|
|
Submit an order with the requested order_id |
|
|
Check the quality of a kitting order with the requested order_id |
|
|
Get the pose of parts on the AGVs prior to assembly for an assembly or combined order with order_id |
|
|
Move the AGV |
|
|
Lock a kit tray to AGV |
|
|
Unlock a kit tray to AGV |
|
|
Set the state of |
|
|
Change the type of |
Message Definitions
- ariac_msgs/msg/AdvancedLogicalCameraImage
ariac_msgs/PartPose[] part_poses ariac_msgs/KitTrayPose[] tray_poses geometry_msgs/Pose sensor_pose
part_poses
: The parts in the camera’s field of viewtray_poses
: The kit trays in the camera’s field of viewsensor_pose
: The pose of the camera in the world frame
- ariac_msgs/msg/AGVStatus
uint8 KITTING=0 uint8 ASSEMBLY_FRONT=1 uint8 ASSEMBLY_BACK=2 uint8 WAREHOUSE=3 uint8 UNKNOWN=99 int8 location float64 position float64 velocity
location
: The location of the AGV. One of the following values:KITTING
: The AGV is at the kitting stationASSEMBLY_FRONT
: The AGV is at the front assembly station (AS1
orAS3
)ASSEMBLY_BACK
: The AGV is at the back assembly station (AS2
orAS4
)WAREHOUSE
: The AGV is at the warehouseUNKNOWN
: The AGV is at an unknown location
position
: The current position of the AGV in the workcellvelocity
: The current velocity of the AGV
- ariac_msgs/msg/AssemblyPart
ariac_msgs/Part part geometry_msgs/PoseStamped assembled_pose geometry_msgs/Vector3 install_direction
part
: The part to be assembledassembled_pose
: The pose of the part in the assembly stationinstall_direction
: The direction the part should be installed in the assembly station
- ariac_msgs/msg/AssemblyState
bool battery_attached bool pump_attached bool sensor_attached bool regulator_attached
battery_attached
: True if battery is attached to the assembly insert, False otherwisepump_attached
: True if pump is attached to the assembly insert, False otherwisesensor_attached
: True if sensor is attached to the assembly insert, False otherwiseregulator_attached
: True if regulator is attached to the assembly insert, False otherwise
- ariac_msgs/msg/AssemblyTask
uint8 AS1=1 uint8 AS2=2 uint8 AS3=3 uint8 AS4=4 uint8[] agv_numbers uint8 station ariac_msgs/AssemblyPart[] parts
agv_numbers
: The AGVs which contain parts for assemblystation
: The assembly station to assemble the parts at. One of the following values:AS1
: The front assembly station for AGV 1 and 2AS2
: The back assembly station for AGV 1 and 2AS3
: The front assembly station for AGV 3 and 4AS4
: The back assembly station for AGV 3 and 4
parts
: The parts to be assembled
See also
- ariac_msgs/msg/BasicLogicalCameraImage
geometry_msgs/Pose[] part_poses geometry_msgs/Pose[] tray_poses geometry_msgs/Pose sensor_pose
part_poses
: The poses of the parts in the camera’s field of viewtray_poses
: The poses of the kit trays in the camera’s field of viewsensor_pose
: The pose of the camera in the world frame
See also
- ariac_msgs/msg/BinInfo
uint8 BIN1=1 uint8 BIN2=2 uint8 BIN3=3 uint8 BIN4=4 uint8 BIN5=5 uint8 BIN6=6 uint8 BIN7=7 uint8 BIN8=8 uint8 bin_number ariac_msgs/PartLot[] parts
bin_number
: The bin number. One of the following values:BIN1
: The first binBIN2
: The second binBIN3
: The third binBIN4
: The fourth binBIN5
: The fifth binBIN6
: The sixth binBIN7
: The seventh binBIN8
: The eighth bin
parts
: The parts in the bin
See also
- ariac_msgs/msg/BinParts
ariac_msgs/BinInfo[] bins
bins
: List of bins and their contents
See also
- ariac_msgs/msg/BreakBeamStatus
std_msgs/Header header bool object_detected
header
: The header of the messageobject_detected
: Is an object detected?
- ariac_msgs/msg/CombinedTask
uint8 AS1=1 uint8 AS2=2 uint8 AS3=3 uint8 AS4=4 uint8 station ariac_msgs/AssemblyPart[] parts
station
: The assembly station to assemble the parts at. One of the following values:AS1
: The front assembly station for AGV 1 and 2AS2
: The back assembly station for AGV 1 and 2AS3
: The front assembly station for AGV 3 and 4AS4
: The back assembly station for AGV 3 and 4
parts
: The parts to be assembled
See also
- ariac_msgs/msg/CompetitionState
uint8 IDLE=0 uint8 READY=1 uint8 STARTED=2 uint8 ORDER_ANNOUNCEMENTS_DONE=3 uint8 ENDED=4 uint8 competition_state
competition_state
: The current state of the competition. One of the following values:IDLE
: The competition is idleREADY
: The competition is ready to startSTARTED
: The competition has startedORDER_ANNOUNCEMENTS_DONE
: The competition has started and all orders have been announcedENDED
: The competition has ended
- ariac_msgs/msg/ConveyorBeltState
float64 power bool enabled
power
: The power of the conveyor beltenabled
: Is the conveyor belt enabled?
- ariac_msgs/msg/ConveyorParts
ariac_msgs/PartLot[] parts
parts
: The parts on the conveyor
See also
- ariac_msgs/msg/HumanState
geometry_msgs/Point human_position geometry_msgs/Point robot_position geometry_msgs/Vector3 human_velocity geometry_msgs/Vector3 robot_velocity
human_position
: The position of the human in the workcellrobot_position
: The position of the ceiling robot in the workcellhuman_velocity
: The velocity of the human in the workcellrobot_velocity
: The velocity of the ceiling robot in the workcell
- ariac_msgs/msg/KittingPart
uint8 QUADRANT1=1 uint8 QUADRANT2=2 uint8 QUADRANT3=3 uint8 QUADRANT4=4 ariac_msgs/Part part uint8 quadrant
part
: The part to be placed in the kitquadrant
: The quadrant of the kit to place the part in. One of the following values:QUADRANT1
: The first quadrant of the kitQUADRANT2
: The second quadrant of the kitQUADRANT3
: The third quadrant of the kitQUADRANT4
: The fourth quadrant of the kit
- ariac_msgs/msg/KittingTask
uint8 KITTING=0 uint8 ASSEMBLY_FRONT=1 uint8 ASSEMBLY_BACK=2 uint8 WAREHOUSE=3 uint8 agv_number int8 tray_id uint8 destination ariac_msgs/KittingPart[] parts
agv_number
: The AGV number to deliver the kit to (1, 2, 3, or 4)tray_id
: The tray number to deliver the kit to (1, 2, 3, 4, 5, or 6)destination
: The destination of the kit. One of the following values:KITTING
: The kit is to be delivered to the kitting stationASSEMBLY_FRONT
: The kit is to be delivered to the front assembly station (as1
oras3
depending on the AGV number)ASSEMBLY_BACK
: The kit is to be delivered to the back assembly station (as2
oras4
depending on the AGV number)WAREHOUSE
: The kit is to be delivered to the warehouse
parts
: The parts to be placed in the kit
See also
- ariac_msgs/msg/KitTrayPose
int8 id geometry_msgs/Pose pose
id
: The ID of the kit traypose
: The pose of the kit tray
See also
- ariac_msgs/msg/Order
uint8 KITTING=0 uint8 ASSEMBLY=1 uint8 COMBINED=2 string id uint8 type # KITTING, ASSEMBLY, or COMBINED bool priority ariac_msgs/KittingTask kitting_task ariac_msgs/AssemblyTask assembly_task ariac_msgs/CombinedTask combined_task
id
: The unique identifier for the ordertype
: The type of order. One of the following:KITTING
: A kitting orderASSEMBLY
: An assembly orderCOMBINED
: A combined order
priority
: Whether the order is a priority orderkitting_task
: The kitting task for the orderassembly_task
: The assembly task for the ordercombined_task
: The combined task for the order
- ariac_msgs/msg/Part
uint8 RED=0 uint8 GREEN=1 uint8 BLUE=2 uint8 ORANGE=3 uint8 PURPLE=4 uint8 BATTERY=10 uint8 PUMP=11 uint8 SENSOR=12 uint8 REGULATOR=13 uint8 color uint8 type
color
: The color of the part. One of the following values:RED
: The part is redGREEN
: The part is greenBLUE
: The part is blueORANGE
: The part is orangePURPLE
: The part is purple
type
: The type of the part. One of the following values:BATTERY
: The part is a batteryPUMP
: The part is a pumpSENSOR
: The part is a sensorREGULATOR
: The part is a regulator
- ariac_msgs/msg/PartLot
ariac_msgs/Part part uint8 quantity
part
: The partquantity
: The quantity of the part
See also
- ariac_msgs/msg/PartPose
ariac_msgs/Part part geometry_msgs/Pose pose
part
: The partpose
: The pose of the part
See also
- ariac_msgs/msg/QualityIssue
bool all_passed bool missing_part bool flipped_part bool faulty_part bool incorrect_part_type bool incorrect_part_color
all_passed
: True if all parts passed the quality check, False otherwisemissing_part
: True if a part is missing, False otherwiseflipped_part
: True if a part is flipped, False otherwisefaulty_part
: True if a part is faulty, False otherwiseincorrect_part_type
: True if a part has the wrong type, False otherwiseincorrect_part_color
: True if a part has the wrong color, False otherwise
- ariac_msgs/msg/Robots
bool floor_robot bool ceiling_robot
floor_robot
: Is the floor robot enabled?ceiling_robot
: Is the ceiling robot enabled?
- ariac_msgs/msg/Sensors
bool break_beam bool proximity bool laser_profiler bool lidar bool camera bool logical_camera
break_beam
: Is the break beam sensor type enabled?proximity
: Is the proximity sensor type enabled?laser_profiler
: Is the laser profiler type enabled?lidar
: Is the lidar type enabled?camera
: Is the camera type enabled?logical_camera
: Is the logical camera type enabled?
- ariac_msgs/msg/VacuumGripperState
bool enabled bool attached string type
enabled
: Is the suction enabled?attached
: Is an object attached to the gripper?type
: The type of the gripper
- sensor_msgs/msg/Image
std_msgs/msg/Header header uint32 height uint32 width string encoding uint8 is_bigendian uint32 step uint8[] data
See also
- sensor_msgs/msg/LaserScan
std_msgs/msg/Header header float angle_min float angle_max float angle_increment float time_increment float scan_time float range_min float range_max float[] ranges float[] intensities
See also
- sensor_msgs/msg/PointCloud
std_msgs/msg/Header header geometry_msgs/msg/Point32[] points sensor_msgs/msg/ChannelFloat32[] channels
See also
- sensor_msgs/msg/Range
uint8 ULTRASOUND=0 uint8 INFRARED=1 std_msgs/msg/Header header uint8 radiation_type float field_of_view float min_range float max_range float range
See also
Service Definitions
- ariac_msgs/srv/ChangeGripper
uint8 PART_GRIPPER=1 uint8 TRAY_GRIPPER=2 uint8 gripper_type --- bool success string message
gripper_type
: The type of gripper to change to. One of the following values:PART_GRIPPER
: Part gripperTRAY_GRIPPER
: Tray gripper
success
: True if the gripper was changed successfully, False otherwisemessage
: A message describing the result of the service call
- ariac_msgs/srv/GetPreAssemblyPoses
string order_id --- bool valid_id bool agv_at_station ariac_msgs/PartPose[] parts
order_id
: The ID of the order to be submittedvalid_id
: True if the order ID is valid, False otherwiseagv_at_station
: True if the AGV is at the station, False otherwiseparts
: The list of parts to be assembled
See also
- ariac_msgs/srv/MoveAGV
int8 KITTING=0 int8 ASSEMBLY_FRONT=1 int8 ASSEMBLY_BACK=2 int8 WAREHOUSE=3 int8 location --- bool success string message
location
: The location to move the AGV to. One of the following values:KITTING
: Kitting stationASSEMBLY_FRONT
: Assembly station front (AS1
orAS3
depending on the AGV ID)ASSEMBLY_BACK
: Assembly station back (AS2
orAS4
depending on the AGV ID)WAREHOUSE
: Warehouse
success
: True if the AGV was moved successfully, False otherwisemessage
: A message describing the result of the service call
- ariac_msgs/srv/PerformQualityCheck
string order_id --- bool valid_id bool all_passed bool incorrect_tray ariac_msgs/QualityIssue quadrant1 ariac_msgs/QualityIssue quadrant2 ariac_msgs/QualityIssue quadrant3 ariac_msgs/QualityIssue quadrant4
order_id
: The ID of the order to be submittedvalid_id
: True if the order ID is valid, False otherwiseall_passed
: True if all parts in the order passed the quality check, False otherwiseincorrect_tray
: True if the detected tray does not have the correct ID for the order, False otherwisequadrant1
: The quality issue for the first quadrantquadrant2
: The quality issue for the second quadrantquadrant3
: The quality issue for the third quadrantquadrant4
: The quality issue for the fourth quadrant
See also
- ariac_msgs/srv/SubmitOrder
string order_id --- bool success string message
order_id
: The ID of the order to be submittedsuccess
: True if the order was submitted successfully, False otherwisemessage
: A message describing the result of the service call
- ariac_msgs/srv/VacuumGripperControl
bool enable --- bool success
enable
: True to enable the vacuum gripper, False to disable itsuccess
: True if the vacuum gripper was enabled/disabled successfully, False otherwise
- std_srvs/srv/Trigger
--- boolean success string message
success
: True if the service call was successful, False otherwisemessage
: A message describing the result of the service call