Skip to content

Latest commit

 

History

History
66 lines (52 loc) · 4.71 KB

File metadata and controls

66 lines (52 loc) · 4.71 KB

##Module description

This module implements a torque control balancing strategy. It computes the interaction forces at the feet in order to stabilise a desired centroidal dynamics, which implies the tracking of a desired center-of-mass trajectory. A cost function penalizing high joint torques - that generate the feet forces - is added to the control framework.

For details see iCub whole-body control through force regulation on rigid non-coplanar contacts

###Compatibility The repository contains two Simulink models: torqueBalancing.mdl, which is generated by using Matlab R2015b, and torqueBalancing2012b.mdl, which is exported from the previous model to be compatible with Matlab R2012b->now. Also, the controller is tested in simulation by using Gazebo 7.0. Older versions of Gazebo may lead to scarse, or unstable, control performances.

###Launch procedure The procedure to run the torque balancing module is still quite elaborate. Users willing to use the module should follow this list.

  • Set the environmental variable YARP_ROBOT_NAME in the bashrc according to the robot one wants to use (e.g. icubGazeboSim for simulations, or iCubGenova01, iCubParis01, etc. for experiments).
  • (Simulation only) Launch yarpserver.
  • (Simulation only) Launch gazebo. If you want to use the synchronization between the controller and the simulator to avoid real-time factor related problems, launch gazebo as follows: gazebo -slibgazebo_yarp_clock.so
  • Bring the robot in a suitable home position (e.g. $ yarpmotorgui --from homePoseBalancingLegsZero.ini and then press on the 'Home All' button)
  • Launch wholeBodyDynamicsTree as follows: $ wholeBodyDynamicsTree --autoconnect --robot YARP_ROBOT_NAME_VALUE
  • Execute the sensors calibration script: $ twoFeetStandingIdleAndCalib.sh
  • Open the simulink model torqueBalancing.mdl or torqueBalancing2012b.mdl.
  • Run the module

##Module details ###Configuration file At start, the module calls the initialization file initTorqueBalancing.m. Once open, this file contains some configuration variables. ####General section

  • robotName : name of the robot to connect to, i.e. 'icubGazeboSim' for simulations, or 'icub' for experiments
  • localName: module name. Ports will be opened with this name. Default to matlabTorqueBalancing
  • simulationTime: time of the simulation/experiment
  • USE_QP_SOLVER: if 1, then a QP will be used to generate torques. If 0, classical pseudo-inverse are used
  • LEFT_RIGHT_FOOT_IN_CONTACT: this two-element vector specifies which foot is in contact with the ground at the start fo the module. [1 1]: both feet in contact, [1 0] left foot in contact; [0 1] right foot in contact;
  • DEMO_MOVEMENTS: if equal to 1 and the robot is standing on double support, then it will perform the classical left-and-right.

####Gains The gains for the robot specified by the variable YARP_ROBOT_NAME can be found in the folder robots/YARP_ROBOT_NAME/gains.m. This file contains several gains, among which

  • maxTorque: saturations to be applied to the output torques. It must be a positive value.
  • gain.PCOM: proportional gains. 3 values
  • gain.DCOM: derivative gains. 3 values
  • gain.ICOM: integral gains. 3 values
  • gain.PAngularMomentum: gain used for the desired rate of change of the momentum. One value
  • impTorso, impArms, impLeftLeg, impRightLeg: gains for the impedance (low level) task. The number must match the number of torque controlled joints.

The latter five gains can be chosen differently for one foor, or two feet balancing.

CoM reference

It is possible to send a CoM reference by connecting to the streaming port comDes:i. The port expects 9 elements: 3 values for the desired CoM position, 3 values for the desired CoM velocity and 3 values for the desired CoM acceleration

Joint reference

It is possible to send the impedance resting position as a reference to the streaming port qdes:i. This port expects the same number of element as the torque controlled joints. References are in radians

Citing this contribution

In case you want to cite the content of this module please refer to iCub whole-body control through force regulation on rigid non-coplanar contacts and use the following bibtex entry:

 @article{Nori_etal2015,
 author="Nori, F. and Traversaro, S. and Eljaik, J. and Romano, F. and Del Prete, A. and Pucci, D.",
 title="iCub whole-body control through force regulation on rigid non-coplanar contacts",
 year="2015",
 journal="Frontiers in {R}obotics and {A}{I}",
 volume="1"
 }