To install the tool, type:
pip install aurt
or, if plotting and visualization features are needed,
pip install aurt[vis]
The following shows the different use cases that aurt supports. In order to improve performance, the model is compiled in different stages, in a way that allows the user to try alternative joint dynamics models without having to re-create the full model, which is a computationally demanding procedure.
aurt compile-rbd --mdh mdh.csv --out rigid_body_dynamics
Reads the Modified Denavit-Hartenberg (MDH) parameters in file mdh.csv
and outputs rigid-body dynamics model to file rigid_body_dynamics
.
The generated model does not include the joint dynamics.
To visualize the kinematics of the robot, make sure the roboticstoolbox-python
is installed, and add the argument --plot
to the compile-rbd
command.
aurt compile-rd --model-rbd rigid_body_dynamics --friction-torque-model square --friction-viscous-powers 2 1 4 --out robot_dynamics
Reads the rigid-body dynamics model created with the compile-rbd
command, and generates the robot dynamics model,
taking into account the joint dynamics configuration.
The friction configuration options are:
--friction-torque-model TYPE
whereTYPE in {none, square, absolute}
are depicted in the figure below for, respectively, parts (a), (b), and (c).
-
--friction-viscous-powers POWERS
wherePOWERS
is a set of integers having the formatP1 P2 ...
used to define the odd polynomial function in the angular velocity of any joint aswith the viscous coefficient of friction corresponding to the integer element of , if is even and otherwise.
aurt calibrate --model robot_dynamics --data measured_data.csv --gravity GX GY GZ --out-params calibrated_parameters.csv --out-calibrated-model rd_calibrated --plot
Reads; 1) the model produced by the compile-rd
command, 2) the measured data in measured_data.csv
, and 3) the gravity components GX GY GZ
(0 0 -9.81
if the robot is "table mounted", i.e. having the axis of rotation for the first joint parallel to the direction of the gravitational acceleration) and writes; 1) the values of the calibrated base parameters to calibrated_parameters.csv
and 2) the calibrated robot dynamics model to rd_calibrated
.
The gravity vector determines the orientation of the robot base for which the parameters will be calibrated.
For showing the calibration plot, use the argument --plot
.
The measured data should contain the following fields:
timestamp
of type float, representing the number of seconds passed from a given reference point.actual_q_j
of type float, representing thej
th joint angle, as measured by the robot controller, wherej
is an integer in{0, 1, ..., N}
.actual_current_j
of type float, representing thej
th joint current, as measured by the robot controller, wherej
is an integer in{0, 1, ..., N}
.
aurt predict --model rd_calibrated --data measured_data.csv --gravity GX GY GZ --out predicted_output.csv
Reads; 1) the model produced by the calibrate
command,
2) the measured data in measured_data.csv
, and
3) the gravity components GX GY GZ
, e.g. 0 0 -9.81
if the robot is "table mounted", i.e. having the axis of rotation for the first joint parallel to the direction of the gravitational acceleration,
and writes the predicted output to predicted_output.csv
.
The prediction fields are:
timestamp
of type float, referring to the time of the measured data, as in Calibrate.predicted_current_j
of type float, representing thej
th joint current as predicted by the modelrd_calibrated
, wherej
is an integer in{0, 1, ..., N}
.
aurt calibrate-validate --model robot_dynamics --data measured_data.csv --gravity GX GY GZ --calibration-data-rel FRACTION --out-params calibrated_parameters.csv --out-calibrated-model rd_calibrated --out-prediction predicted_output.csv --plot
Simultaneously calibrates and validates the robot dynamics model using the dataset measured_data.csv
.
The command implements the functionalities of the commands calibrate
and predict
.
The data of measured_data.csv
is separated into two consecutive parts 1) calibration data and 2) validation data.
The calibration data has a duration of 0.1 < FRACTION
< 0.9 times the duration of measured_data.csv
while the remaining part of the data is used for validation.
It is possible to obtain Functional Mockup Units (FMUs) of a calibrated robot dynamics model (obtained using either of the commands aurt calibrate
and aurt calibrate-validate
). This work is based on UniFMU. There is a limit of 10 on the maximum allowed number of robot joints.
Two types of FMUs are available distinguished by the model type, i.e. which quantities are considered as inputs and which are considered as outputs:
- Forward Dynamics Model, sometimes referred to as Direct Dynamics Model (DDM). It is an Initial Value Problem (IVP) with input and outputs and , thus initial values and need be provided. If any joint torque-dependent friction model is present it will be removed, i.e. for each joint the friction , because otherwise it would not be possible to obtain the closed-form expression .
- Inverse Dynamics Model (IDM). It's a closed-form expression with inputs , , and and output . The output with .
To generate an FMU:
- Copy or move the calibrated robot dynamics model
rd_calibrated.pickle
to either of the folders./fmu/forward_dynamics/resources/
or./fmu/inverse_dynamics/resources/
depending on the desired FMU type. Note that the filename of the robot dynamics must berd_calibrated.pickle
. - Construct a zip archive containing all contents in either of the folders
./fmu/forward_dynamics/
or./fmu/inverse_dynamics/
depending on the desired FMU type. - Change the file extension of the zip archive from
.zip
to.fmu
.
To setup the development environment:
- Open terminal in the current folder.
- Install all packages for development:
pip install -e .[vis]
. - Unpack the datasets (see Dataset management)
- To run all non live tests, open a command prompt or powershell in the repository root, and run
python build.py --run-tests all-non-live
. If you are using Linux, usepython3
instead ofpython
.
NOTE: Run tests before commits. If they don't pass, fix them before committing.
- Update version in
setup.py
- Make sure all tests, except the live ones, are passing.
- Delete folders
dist
build
if they exist. - Activate virtual environment.
- Install twine and wheel:
pip install twine wheel
- Create a source distribution:
python setup.py sdist
- Create the binary distribution:
python setup.py bdist_wheel
- Upload distribution to PyPI:
python -m twine upload dist/*
(on Windows, use Command Prompt for this command) - When asked for username and password, use the token and password created with your PyPI account.
If the data is small, then:
- Each round of experiments should be placed in a folder with an informative name, inside the Dataset folder.
- There should be a readme file in there explaining the steps to reproduce the experiment, parameters, etc...
- The csv files should be 7ziped and committed. Do not commit the csv file.
- There should be tests that use the data there.
If the data is large, then:
- A "lite" version of the dataset should be in the dataset folder (following the same guidelines as before)
- This is important to run the tests.
- the larger version should be placed in the shared drive (see below).
There is a shared drive for large datasets. The shared drive Nat_robot-datasets has been created with Emil Madsen as owner.
Shared Drive | Owner | Department | |
---|---|---|---|
Nat_robot-datasets | au504769 (Emil Madsen) | ema@ece.au.dk | Electrical and Computer Engineering (ECE) |
Read/write access is assigned to:
Username | Name | Department | |
---|---|---|---|
au602135 | Cláudio Ângelo Gonçalves Gomes | claudio.gomes@ece.au.dk | Electrical and Computer Engineering (ECE) |
au522101 | Christian Møldrup Legaard | cml@ece.au.dk | Electrical and Computer Engineering (ECE) |
au513437 | Daniella Tola | dt@ece.au.dk | Electrical and Computer Engineering (ECE) |
For more information on access, self-service and management of files: https://medarbejdere.au.dk/en/administration/it/guides/datastorage/data-storage/