icub-test
Public Member Functions
JointLimits Class Reference

Check if the software joint limits are properly set. More...

#include <jointLimits.h>

Inherits yarp::robottestingframework::TestCase.

Public Member Functions

virtual bool setup (yarp::os::Property &property)
 
virtual void tearDown ()
 
virtual void run ()
 
void goTo (yarp::sig::Vector position)
 
bool goToSingle (int i, double pos, double *reached_pos)
 
bool goToSingleExceed (int i, double position_to_reach, double limit, double reachedLimit, double *reached_pos)
 
void setMode (int desired_mode)
 
void saveToFile (std::string filename, yarp::os::Bottle &b)
 

Detailed Description

Check if the software joint limits are properly set.

The limits are set in the robot configuration files. The test asks the limits to robotInterface using the IControlLimits interface. The test moves each joint first to the max lim, then to the min lim, then to home. If the joint is unable to reach the software limits within a certain tolerance, the test fails and the joint is put back in home position. The timeout for each joint to reach the limit position is fixed to 20 seconds. The test uses an limited output to avoid to damage the joint if, for example, an hardware limit is reached before the software limit. If this limit is too small, the the joint may be unable to reach the limit (e.g. because of friction), so the value must be chosen accurately. The test assumes the the position control is properly working and the position pid is properly tuned. After testing the limits, this test also tries to move the joint out of the limits on puropose (adding to the joint limits the value of outOfBoundPosition). The test is successfull if the position move command is correctly stopped at the limit.

Example: testRunner -v -t JointLimits.dll -p "--robot icub --part head --joints ""(0 1 2)"" --home ""(0 0 0)"" --speed ""(20 20 20)"" --outputLimitPercent ""(30 30 30)"" --outOfBoundPosition ""(2 2 2)"" --tolerance 0.2"

Check the following functions:

Support functions:

Accepts the following parameters:

Parameter name Type Units Default Value Required Description Notes
robot string - - Yes The name of the robot. e.g. icub
part string - - Yes The name of trhe robot part. e.g. left_arm
joints vector of ints - - Yes List of joints to be tested
home vector of doubles of size joints deg - Yes The home position for each joint
speed vector of doubles of size joints deg/s - Yes The reference speed used furing the movement
tolerance vector of doubles of size joints deg - Yes The position tolerance used to check if the limit has been properly reached. Typical value = 0.2 deg.
outputLimitPercent vector of doubles of size joints % - Yes The maximum motor output (expressed as percentage). Safe values can be, for example, 30%.
outOfBoundPosition vector of doubles of size joints % - Yes This value is added the joint limit to test that a position command is not able to move out of the joint limits Typical value 2 deg.

Definition at line 74 of file jointLimits.h.


The documentation for this class was generated from the following files: