The below describes the calibration method for Beta RapidSense release. This requires some manual work and ensuring the cal.json file is configured and stored in the directory: ~/.config/rapidsense. In the future RapidSense release, the process will include a GUI and be much more user friendly.
Overview
The current method uses the robot to calibrate the sensors. The robot will need to hold a calibration tag and move through positions with the tag in the sensors field of view during calibration process. The positions will need to be set by the user. Optionally, a calibration tag will also need to be mounted stationary in the scene in the field of view of the sensors in order for the system to be able to detect if the sensors have shifted out of calibration.
The cal.json file contains all the relevant information to calibrate and run the RapidSense system with multiple cameras.
Calibration Requirements
The requirements for calibration are:
Aruco tag mounted off of the robot faceplate
Static Aruco tag placed in the scene which is easily visible to the sensor
Calibration preset in RPC called “Calibration” with accurate TCP frame located at the center of the Aruco tag.
For calibrating, create a frame on the aruco tag face center with its X axis (Red) pointing to the right, Y (Green) pointing upwards and Z (Blue) coming out of the face. Something like this:
cal.json file which has all the camera serial_numbers and each sensor’s corresponding robot target position for calibration which have the Aruco tag on the robot in the sensor field of view
A home robot target position with the following naming convention: robotname_home.
The calibration robot target positions present in cal.json should be connected on Roadmap to the home target in RPC project in order for the calibration to succeed.
Setup and Running Calibration Process Manually
To easily generate the cal.json file and save it in ~/.config/rapidsense, there is a calibration_generator.py script which prompts the user for all the necessary information and generates the cal.json file. Run the calibration_generator.py script by typing “calibration_generator.py” in the command line of the terminal and follow the prompts to create a cal.json file. The below is an example of the prompts to the user and responses.
Enter the number of sensors you want to add: 2 ******************** Entering Data For New Camera ******************** Enter Serial Number: xyz Enter Robot Mounted Aruco ID: 1 Enter Length for Robot Mounted Tag (meters): 0.09 Enter Robot name: Fanuc Enter Calibration Target: fanuc_cal Static marker exists for this camera? y or n : n ******************** Entering Data For New Camera ******************** Enter Serial Number: abc Enter Robot Mounted Aruco ID: 2 Enter Length for Robot Mounted Tag (meters): 0.09 Enter Robot name: UR Enter Calibration Target: cal_target_UR Static marker exists for this camera? y or n: y Enter Stationary ID: 4 Enter Length of Stationary Tag (meters): 0.09
After the cal.json file has been generated, run the calibration_service.py script and go to localhost:9000/calibration to calibrate all the cameras after rapidsense and rtr_rapidsense_proxy services are running or go to the RapidSense Monitor interface. The calibration script will pull in information from the cal.json file and make the robots move to the cal_targets sequentially, extrinsically calibrating all corresponding cameras. The robot will then return to the home location and all the cameras will save the pose of the static marker placed in the scene. After a successful calibration, all the values will be automatically updated in the cal.json file.
Current calibration implementation looks like this and follows these states:
from state import * from statemachine import StateMachine from controller import Controller class CalibrationSequence(StateMachine): def __init__(self, steps, robot_name): states = list() for data in steps: states.append(MoveToTarget(data["cal_target"])) states.append(Calibrate(data["serial_number"])) states.append(MoveToTarget(robot_name + "_home")) states.append(StaticCalibrate("stationary")) StateMachine.__init__(self, states, robot_name)
The following prerequisites should be met before running calibration:
All robots should be at their home positions (target names should follow this naming “[robotname]_home”) before starting to calibrate
The user should make sure that the robots do not block the static marker when in home positions
rapidsense and rtr_rapidsense_proxy services are running
Running Calibration from RapidSense Monitor
In the Settings page of the RapidSense Monitor, there is a button available which will run the calibration service and process. A user will need to make sure that the robot is at the “[robotname]_home” target position before being able to run the process. A warning message will pop up to warn a user to ensure the calibration tag is attached to the robot and that the robot will move once it is confirmed to calibrate.
Calibration ASCII Interface
'topic': 'Calibrate', 'data': { 'serial_number' : serial_number, 'tcp_pose' : tcp_pose }
The calibration ASCII command { 'topic': 'Calibrate', 'data': { 'serial_number' : serial_number, 'tcp_pose' : tcp_pose } } is used where the serial_number is the camera to be calibrated and the TCP_pose is for the associated robot with the tag mounted on it. These values are sent over the proxy to rapidsense where Aruco detection algorithm finds the markers which allows for calibration of the sensors to occur. Before sending this command, the proper calibration robot preset must be active.
After successful calibration, the pose of the static marker is found and saved in the file cal.json. GetRapidSenseStatus is set as true for the is_calibrated for the corresponding sensor.
Continuous Calibration Checking Functionality
During the calibration process, the static Aruco tag in the scene is found and the image is cached to compare against during system running in order to detect when the sensors may have been shifted out of calibration. When it is detected that a sensor may have been shifted out of calibration, GetRapidSenseStatus is set to false for Is_calibrated for that particular sensor in order to warn the user that the calibration needs to be adjusted and run again.
Check the configuration
After the calibration check of the system is properly configured, use ScanScene command to show obstacles detected by RapidSense. Verify that the detected obstacles match the actual cells. Incorrect orientation of the calibration tag may result in the following.
Sample cal.json File for (2) Sensors, (1) Sensor with Continuous Calibration Checking
{ "calibration": [ { "extrinsics": [ 1.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 1.0 ], "serial": "xyz", "marker": { "robot_mounted": { "id": 1, "length": 1.0, "robot": "Fanuc", "cal_target": "fanuc_cal" } } }, { "extrinsics": [ 1.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 1.0 ], "serial": "abc", "marker": { "robot_mounted": { "id": 2, "length": 2.0, "robot": "UR", "cal_target": "cal_target_UR" }, "stationary": { "id": 4, "length": 0.1, "pose": [ 1.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 1.0 ] } } } ] }