This repository contains instructions and necesssary files for setting up a workspace to perform automated testing of material removal using a pneumatic grinder.
The .repos
file contain references to all repositories (excluding dependencies) required to operate either stationary grinding tests or robot-arm mounted grinding tests.
The following are the repositories that will be installed using .repos
:
data_gathering
: Contain main launch file for the test, and control the grinderstamped_std_msgs
: Stamped standard messages for data storagedata_gathering_msgs
: Additional msgsur_trajectory_controller
: Controls the UR16escancontrol
: ROS2 Driver for Scancontrol laser line scannerslls_processing
: Compiles 3D pointcloud reconstructions based on TF transferspcl_processing_ros2
: Used to calculate volume loss between two scansUniversal_Robots_ROS2_Driver
: Driver for the UR16eferrobotics_acf
: Controls the ACFgrinder_model
: Python script for training and evaluating predictive model with test databag_converter
: Python script for postprocessing test data from rosbag into .csv datarws_motion_client
: Client node controlling ABB robot arm motion using the ABB robot driver: (abb_ros2
).
CAUTION: rws_motion_client
is a repository for moving grinder on a robot, and for grinder on a robot, the following repositories also need to be checked out in moving-grinder branch:
data_gathering
, data_gathering_msgs
, pcl_processing_ros2
, grinder_model
, and bag_converter
.
The requirement.txt
and .pkglist
contains all python and apt dependencies required for all the repositories outlined in the .repos
file:
ros-humble-rosbag2-storage-mcap
: Enabled MCAP storage format for rosbagsopen3d
: for pointcloud operations. Note that the used (and currently latest) version requires Numpy < 1.25. Used inpcl_processing_ros2
andlls_processing
.libsdl2-dev
: Simple DirectMedia Layer(SDL) 2.0 for keyboard repositorypyads
: A Python wrapper for TwinCAT ADS library. Used indata_gathering
concave_hull
: A Python library to calculate concave hulls. Used inpcl_processing_ros2
pyransac3d
: A python library for the RANSAC algorithm. Used inpcl_processing_ros2
For the grinder_automation repositories to work, the following Third party repositories are also required to be built:
keyboard_msgs
: keyboard ROS2 messages for UR trajectory recording. Used inur_trajectory_controller
. Installation instruction uses a fork created by Luka140abb_ros2
: ABB robot ROS2 driver. Used inrws_motion_client
. Installation instruction uses a fork created by panin-anan
Aside from above dependencies, the following third party packages are also required to be installed as dependencies by using setup_scancontrol.sh
on your docker.
see Installation section for installation instructions
To install the repositories, navigate to your workspace source folder again (e.g., ~/workspace_folder/src)
cd src
clone this repositories to your workspace source folder
and run vcs import using the path to the .repos
file, for example the author workspace name is 'BrightSkyRepoLinux':
git clone https://github.com/Luka140/grinder-automation.git
vcs import < /workspaces/BrightSkyRepoLinux/src/grinder-automation/.repos
NOTE: For robot-arm mounted grinding test setup, check out moving-grinder branch of this repository.
To install the dependencies
$DEV_WORKSPACE/src/grinder-automation/setup.sh
cd src
git clone https://github.com/Luka140/ros2-keyboard.git
git clone https://github.com/panin-anan/abb_ros2.git -b humble
vcs import < abb_ros2/abb.repos
rosdep install -r --from-paths . --ignore-src --rosdistro $ROS_DISTRO -y
cd ..
To install aravis and scancontrol SDK with setup_scancontrol.sh
:
$DEV_WORKSPACE/src/grinder-automation/setup_scancontrol.sh
To build all the packages, follow below sequence because some repositories are dependent on the ROS2 message type repositories
colcon build --packages-select stamped_std_msgs --symlink-install
colcon build --packages-skip rws_motion_client --symlink-install
source install/setup.bash
colcon build --packages-select rws_motion_client --symlink-install
source install/setup.bash
For more information on the usage, Check out https://github.com/Luka140/data_gathering
This grinder-automation repository works with the following hardware setup for an automated grind:
- PLC computer: CX8190 from
Beckhoff Automation
- Universal Robot Arm: UR16e from
Universal Robots
- Active Contact Flange: ACF-K from
Ferrobotics
- Laser Line Scanner: scanControl 29x0 from
micro-epsilon
- ABB Robot Arm: (for moving grinder) ABB IRB-1200 from
ABB Robotics
PLC computer also contains extra IO Field Buses as necessary to connect to a flow control valve
, which controls the flow rate and RPM of the Dynafile
grinding power tool
A picture showing an example of automated grinding test setup is shown below:
First, source installed packages
source install/setup.bash
Before running the entire system, we can check each component by launching the following drivers one by one:
ros2 launch ur_trajectory_controller ur_driver.launch.py
ros2 launch ferrobotics_acf acf.launch.py
ros2 launch micro_epsilon_scancontrol_driver load_driver.launch.py
When all components are confirmed to be connectable to the actual hardware, launch with data_gathering launch file with the following launch parameters:
ros2 launch data_gathering data_gathering.launch.py
Launch Parameters Example:
-
sample = "sample_name_input" (String)
-
plate_thickness = 0.002 (float, in meters)
-
grit = 120 (float)
-
belt_width = 0.025 (float, in meters)
-
pass_length = 0.1 (float, in meters)
-
force_settings = [5, 6, 7] (float 1D array, in Newtons)
-
rpm_settings = [9500, 10000] (float 1D array, in rev/min)
-
feed_rate_settings = [20, 30] (float 1D array, in mm/s)
-
pass_count_settings [10, 15] (int 1D array)
-
repeat_test_count = 1 (int, number of test repeat before scanning for volume removed)
-
all_setting_permutations = False (bool, permutate all possible setting from array if True, go by index if False)
-
initially_prime_new_belt = False (bool, prime belt before grinding)
-
wear_threshold = 5e7 (float, threshold before forcing to change grinding belt)
-
feed_rate_threshold = 45 (float, threshold for setting feed_rate_settings)
-
belt_wear_path = "src/data_gathering/data/belt_data/beltid_14_grit_120.csv" (String, path to belt wear tracking file .csv)
-
motion_client node: 'grinder_spinup_duration' = 4 (float, waiting time before moving grinding belt to the first grind position)
-
acf_node: 'payload' = 2.0 (weight of the parts on acf (in kg), for gravity compensation)