Item | Quantity | URL/Notes | Cost |
---|---|---|---|
3D printer | 1 | With a front mounted extruder motor (Origianl Prusa i3 MK2 was used - no longer on sale) | --- |
Spool of PLA | 1 | https://www.amazon.co.uk/eSUN-Filament-Dimensional-Accuracy-Printers/dp/B0CHDSB6LQ/ref=sr_1_12?sr=8-12 | £15 |
M4 Screws | 4 | https://www.amazon.co.uk/newlng-1180Pieces-Screws-Carbon-Washers/dp/B09YLMQFQV/ref=sr_1_1_sspa?sr=8-1-spons&sp_csd=d2lkZ2V0TmFtZT1zcF9hdGY&psc=1 | £12 |
15cm Metal Ruler | 1 | https://www.amazon.co.uk/Draper-Expert-22670-6-inch-Stainless/dp/B008RXSAM2 | £4 |
Rubber Sheet (optional) | 1 | https://www.amazon.co.uk/Adhesive-Ferrite-Ferrous-Magnetic-Movement/dp/B0722VX2N5/ref=sr_1_3?s=diy&sr=1-3 | £7.50 |
Item | Quantity |
---|---|
Whisker Sensor Mount | 1 |
Whisker Sensor Adaptor | 1 |
End Effector Mount | 1 |
Item |
---|
Allen keys |
Phillips head screwdriver |
-
Print the following parts:
- End Effector Mount
- Whisker Sensor Adaptor
- End Effector Mount
These can becalibration_platform/hardware/End Effector Mount.stl found at
calibration_platform/hardware/
-
Attach the Whisker Sensor Adaptor to the rear end of the printer base (optionally use a sheet to rubber between the adaptor and the printer base for increased resistance and protection from the screws)
-
Attach the End Effector Mount and Beam
- Remove the screws from the extruder motor
- Screw the End Effector Mount into the extruder motor
- Place the Ruler into the slot
-
Measurements: It is important to take note of a few measurements to allow effective testing.
- Beam positioning and dimensions
BEAM_THICKNESS
: width of the ruler (or any alternative beam used)BEAM_EDGE_Y_RELATIVE_TO_NOZZLE
: y distance of the beam relative to the nozzleBEAM_START
: x distance of the right-most edge of the beam relative to the nozzle
- Whisker positioning and dimensions
WHISKER_X
: x position of the whisker on the printing bedWHISKER_LENGTH_Y
: length of the whisker being evaluatedWHISKER_TIP_Y
: y distance of the beam at the edge tip of the whisker
These measurements should be modified within the printer controller, located at calibration_platform/software/GCodeController/GcodeController.py
, based on your testing setup. This is to allow the configuration to be quite flexible for any printer, any beam position and any whisker being tested. This also allows the beam to be mounted however you would like so long as it is vertically placed.
To calibrate the sensor for radial contact distance inference, run the following commands in the whisker_driver_ros2 folder.
Install ROS2 environment following this instruction. Then run:
> scripts/install_deps.sh
> colcon build && . install/setup.bash
- Connect the 3D printer to the host computer via a serial connection (i.e. using the USB interface in this case)
- Identify the serial port of the 3D printer on the computer. By default, it is set to locate the serial port at
/dev/ttyACM0
. Check for the new port connection by running:ls /dev/tty*
- Now connect the whisker sensor to another USB port. Run again
ls /dev/tty*
and note down the newly appeared port. It is likely to be/dev/ttyACM1
.
The port names are then used in the following ros2 commands.
Launch whisker sensor driver node
> ros2 run whisker_driver_node whisker_driver_node --ros-args -p serial_device:=/dev/ttyACM0 -p whisker_model_path:=$(pwd)/whisker_driver_ros2/scripts/whisker_model.pkl
Launch 3d printer driver node
> ros2 run printer_driver_node printer_driver_node --ros-args -p serial_device:=/dev/ttyACM1
Start recording data on all topics into a rosbag
> ros2 bag record -s mcap --all
Issue a service call to 3d printer to start the calibration routine
> ros2 service call /increments_beam_test whisker_interfaces/IncrementsBeamTest "{total_x_distance: 6, total_y_distance: 100, increments_x: 0, increments_y
: 15, pause_sec: 0}"
WARNING: It is recommended to test the controller WITHOUT the whisker in place first, to understand the behaviors!!
The whisker model is a parametric model to predict contact point along the whisker from sensor reading.
To fit a new whisker model, open and execute this jupyter notebook.
A file named whisker_model.pkl
is produced from the script.
To estimate contact distance in real time, launch whisker_driver_node
:
> ros2 run whisker_driver_node whisker_driver_node --ros-args -p serial_device:=/dev/ttyACM0 -p whisker_model_path:=$(pwd)/whisker_driver_ros2/scripts/whisker_model.pkl
This will load the newly fitted whisker_model.pkl
and use it to infer any contact made on the whisker.
NOTE: Please see software documentation for further details about the software structure and how to adapt the code for different types of calibrations.