Skip to content

Commit

Permalink
Add doxygen documentation
Browse files Browse the repository at this point in the history
  • Loading branch information
martinaxgloria committed Jan 24, 2024
1 parent 5f84b94 commit ad31d2e
Show file tree
Hide file tree
Showing 3 changed files with 31 additions and 4 deletions.
4 changes: 2 additions & 2 deletions src/imu/imu.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ bool Imu::setup(yarp::os::Property& property)
ROBOTTESTINGFRAMEWORK_ASSERT_ERROR_IF_FALSE(property.check("robot"), "The robot name must be given as the test parameter!");
ROBOTTESTINGFRAMEWORK_ASSERT_ERROR_IF_FALSE(property.check("port"), "The port name must be given as the test parameter!");
ROBOTTESTINGFRAMEWORK_ASSERT_ERROR_IF_FALSE(property.check("part"), "The part name must be given as the test parameter!");
ROBOTTESTINGFRAMEWORK_ASSERT_ERROR_IF_FALSE(property.check("remote_controlboards"), "Please, provide the controlboards name.");
ROBOTTESTINGFRAMEWORK_ASSERT_ERROR_IF_FALSE(property.check("controlboards"), "Please, provide the controlboards name.");
ROBOTTESTINGFRAMEWORK_ASSERT_ERROR_IF_FALSE(property.check("model"), "Please, provide the urdf model path.");
ROBOTTESTINGFRAMEWORK_ASSERT_ERROR_IF_FALSE(property.check("frame"), "Please, provide the frame name.");
ROBOTTESTINGFRAMEWORK_ASSERT_ERROR_IF_FALSE(property.check("sensor"), "Please, provide the sensor name.");
Expand Down Expand Up @@ -54,7 +54,7 @@ bool Imu::setup(yarp::os::Property& property)
yarp::os::Bottle remoteControlBoards;
yarp::os::Bottle & remoteControlBoardsList = remoteControlBoards.addList();
yarp::os::Bottle *inputControlBoards;
inputControlBoards = property.find("remote_controlboards").asList();
inputControlBoards = property.find("controlboards").asList();
for (int i = 0; i < inputControlBoards->size(); i++)
{
remoteControlBoardsList.addString("/"+robotName+"/"+inputControlBoards->get(i).asString());
Expand Down
29 changes: 28 additions & 1 deletion src/imu/imu.h
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,34 @@
#include <iDynTree/ModelLoader.h>
#include <iDynTree/Model.h>

/**
* \ingroup icub-tests
*
* The purpose of this test is to evaluate the accuracy of the IMU Euler angles measurements.
* It takes as input the urdf of the robot and make a comparison between the expected values retrieved from the forward kinematics and the ones read from the IMU itself.
* The test involves the movements of the joints belonging to the part on which the sensor is mounted. The movements are executed sequentially, traversing from the home position to the lower limit, upper limit and back to the home position for each joint.
*
* Example: robottestingframework-testrunner --test plugins/imu.so --param "--robot icub --model model.urdf --port /icub/head/inertials --part head --controlboards ("torso", "head") --sensor head_imu_0 --frame head_imu_0 --mean_error 0.1"
*
* Moreover, you can manually modify the suites/contexts/icub/test_imu.ini file depending on the parameters of the test. In this case, after compiling, you can run:
*
* robottestingframework-testrunner --suite ../suites/imu.xml
*
* This will launch the test and open a yarpscope with the plots of the IMU traces.
*
* Accepts the following parameters:
* | Parameter name | Type | Units | Default Value | Required | Description | Notes |
* |:------------------:|:------------------:|:-----:|:-------------:|:--------:|:-----------:|:-----:|
* | robot | string | - | - | Yes | The name of the robot. | e.g. icub |
* | model | string | - | - | Yes | The name of the robot model. | e.g. model.urdf |
* | port | string | - | - | Yes | The name of the port streaming IMU data. | e.g. /icub/head/inertials |
* | part | string | - | - | Yes | The name of the robot part on which the sensor is mounted. | e.g. head |
* | controlboards | vector of string | - | - | Yes | The list of the controlboards to open. | e.g. ("torso", "head") |
* | sensor | string | - | - | Yes | The name of the sensor to be tested. | e.g. head_imu_0 |
* | frame | string | - | - | Yes | The name of the frame on which the sensor is attached. | e.g. head_imu_0|
* | mean_error | double | - | - | Yes | The tolerance on the mean of the error. | |
*/

class Imu : public yarp::robottestingframework::TestCase {
public:
Imu();
Expand Down Expand Up @@ -49,7 +77,6 @@ class Imu : public yarp::robottestingframework::TestCase {

iDynTree::ModelLoader model;
iDynTree::KinDynComputations kinDynComp;

iDynTree::VectorDynSize s;
iDynTree::VectorDynSize ds;
iDynTree::Vector3 gravity;
Expand Down
2 changes: 1 addition & 1 deletion suites/contexts/icub/test_imu.ini
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ robot ${robotname}
model model.urdf
port /${robotname}/head/inertials
part head
remote_controlboards ("torso", "head")
controlboards ("torso", "head")
sensor head_imu_0
frame head_imu_0
mean_error 0.1

0 comments on commit ad31d2e

Please sign in to comment.