Skip to content

Commit

Permalink
Add the configuration files in order to use the robot without the for…
Browse files Browse the repository at this point in the history
…eArms. (#115)

* Add the configuration files in order use the robot without the foreArms.
All the files have been called with the suffix iRonCub.
There are two start up files:
- iCubGenova04/iRonCub_wbd.xml (iCub without the forearms)
- iCubGenova04/iRonCub-noLegs_wbd.xml (iCub without the torso, without the forearms and without the legs)

Also the file for using wholebodydynamics has been modified, but it
works only for iRonCub_wbd.xml.

The files:
- iCubGenova04/wrappers/motorControl/left_arm-mc_wrapper_iRonCub.xml
- iCubGenova04/wrappers/motorControl/right_arm-mc_wrapper_iRonCub.xml
have been added because we wanted to use accelerometers in the arms.

* Remove the inertials information on the arms

I've commented the lineas of iRonCub-noLegs_wbd.xml and iRonCub_wbd.xml
where the inertials information on the arms have been called

* Modify the *_arm-calib_iRonCub.xml

I've copied the *_arm-calib.xml and then I've changed the `CALIB_ORDER`
parameter removing useless joints.

* Remove all the changes done in the previous commit

Previous commit name: 7c19c60

In particular I did those changes:
- joints param = 4
- table size   = 4

Calib order was already equal to 4

* Update wholebodydynamics configuration files after #116

Co-authored-by: iCubGenova04 <iCubGenova04@example.com>
  • Loading branch information
FabioBergonti and iCubGenova04 committed Mar 10, 2020
1 parent e59be38 commit 1a05e78
Show file tree
Hide file tree
Showing 7 changed files with 513 additions and 0 deletions.
48 changes: 48 additions & 0 deletions iCubGenova04/calibrators/left_arm-calib_iRonCub.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
<?xml version="1.0" encoding="UTF-8" ?>
<!DOCTYPE devices PUBLIC "-//YARP//DTD yarprobotinterface 3.0//EN" "http://www.yarp.it/DTD/yarprobotinterfaceV3.0.dtd">


<device xmlns:xi="http://www.w3.org/2001/XInclude" name="left_arm-calibrator" type="parametricCalibratorEth">
<xi:include href="../general.xml" />

<group name="GENERAL">
<param name="joints">4</param> <!-- the number of joints of the robot part -->
<param name="deviceName"> Left_Arm_Calibrator </param>
</group>

<!-- joint logical number 0 1 2 3 -->

<group name="HOME">
<param name="positionHome"> -30 30 0 45 </param>
<param name="velocityHome"> 10 10 10 10 </param>
</group>

<group name="CALIBRATION">
<param name="calibrationType"> 3 3 3 3 </param>
<param name="calibration1"> 0 0 0 0 </param>
<param name="calibration2"> 0 0 0 0 </param>
<param name="calibration3"> 30431.08 3135.14 6479.08 64526.92 </param>
<param name="calibration4"> 0 0 0 0 </param>
<param name="calibration5"> 0 0 0 0 </param>
<param name="calibrationZero"> -180.00 -315.00 180.00 -180.00 </param>
<param name="calibrationDelta"> 106.4 -9.6 -17.0 -0.8 </param>

<param name="startupPosition"> -35.97 29.97 0.06 50.00 </param>
<param name="startupVelocity"> 10.0 10.0 10.0 10.0 </param>
<param name="startupMaxPwm"> 5000 5000 5000 5000 </param>
<param name="startupPosThreshold"> 2 2 2 2 </param>
</group>

<param name="CALIB_ORDER">(0 1 2 3) </param>

<action phase="startup" level="10" type="calibrate">
<param name="target">left_arm-mc_wrapper</param>
</action>

<action phase="interrupt1" level="1" type="park">
<param name="target">left_arm-mc_wrapper</param>
</action>

<action phase="interrupt3" level="1" type="abort" />

</device>
46 changes: 46 additions & 0 deletions iCubGenova04/calibrators/right_arm-calib_iRonCub.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
<?xml version="1.0" encoding="UTF-8" ?>
<!DOCTYPE devices PUBLIC "-//YARP//DTD yarprobotinterface 3.0//EN" "http://www.yarp.it/DTD/yarprobotinterfaceV3.0.dtd">


<device xmlns:xi="http://www.w3.org/2001/XInclude" name="right_arm-calibrator" type="parametricCalibratorEth">
<xi:include href="../general.xml" />

<group name="GENERAL">
<param name="joints">4</param> <!-- the number of joints of the robot part -->
<param name="deviceName"> Right_Arm_Calibrator </param>
</group>
<!-- joint logical number 0 1 2 3 -->
<group name="HOME">
<param name="positionHome"> -30 30 0 45 </param>
<param name="velocityHome"> 10 10 10 10 </param>
</group>


<group name="CALIBRATION">
<param name="calibrationType"> 3 3 3 3 </param>
<param name="calibration1"> 0 0 0 0 </param>
<param name="calibration2"> 0 0 0 0 </param>
<param name="calibration3"> 21631.1 40063.0 5167.08 4975.08 </param>
<param name="calibration4"> 0 0 0 0 </param>
<param name="calibration5"> 0 0 0 0 </param>
<param name="calibrationZero"> 180.00 45.00 -180.00 180.00 </param>
<param name="calibrationDelta"> 23.8 -7.8 -17.2 -1.3 </param>

<param name="startupPosition"> -35 30 0 50 </param>
<param name="startupVelocity"> 10.0 10.0 10 10 </param>
<param name="startupMaxPwm"> 5000 5000 5000 5000 </param>
<param name="startupPosThreshold"> 2 2 90 90 </param>
</group>

<param name="CALIB_ORDER">(0 1 2 3) </param>
<action phase="startup" level="10" type="calibrate">
<param name="target">right_arm-mc_wrapper</param>
</action>

<action phase="interrupt1" level="1" type="park">
<param name="target">right_arm-mc_wrapper</param>
</action>

<action phase="interrupt3" level="1" type="abort" />

</device>
106 changes: 106 additions & 0 deletions iCubGenova04/estimators/wholebodydynamics_iRonCub.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,106 @@
<?xml version="1.0" encoding="UTF-8" ?>
<!DOCTYPE devices PUBLIC "-//YARP//DTD yarprobotinterface 3.0//EN" "http://www.yarp.it/DTD/yarprobotinterfaceV3.0.dtd">


<device xmlns:xi="http://www.w3.org/2001/XInclude" name="wholebodydynamics" type="wholebodydynamics">
<param name="axesNames">(torso_pitch,torso_roll,torso_yaw,neck_pitch, neck_roll,neck_yaw,l_shoulder_pitch,l_shoulder_roll,l_shoulder_yaw,l_elbow,r_shoulder_pitch,r_shoulder_roll,r_shoulder_yaw,r_elbow,l_hip_pitch,l_hip_roll,l_hip_yaw,l_knee,l_ankle_pitch,l_ankle_roll,r_hip_pitch,r_hip_roll,r_hip_yaw,r_knee,r_ankle_pitch,r_ankle_roll)</param>
<param name="modelFile">model.urdf</param>
<param name="fixedFrameGravity">(0,0,-9.81)</param>
<param name="defaultContactFrames">(root_link,l_sole,r_sole,r_lower_leg,l_lower_leg,l_elbow_1,r_elbow_1)</param>
<param name="imuFrameName">imu_frame</param>
<param name="publishOnROS">true</param>
<param name="forceTorqueEstimateConfidence">2</param>
<param name="useJointVelocity">true</param>
<param name="useJointAcceleration">false</param>
<param name="streamFilteredFT">true</param>

<!-- map between iDynTree links (identified by a name)
and skinDynLib links (identified by their frame name, a BodyPart enum
and a local (to the body part) index -->
<group name="IDYNTREE_SKINDYNLIB_LINKS">
<param name="root_link">(root_link,1,0)</param>
<param name="chest"> (chest,1,2)</param>
<param name="l_upper_arm">(l_upper_arm,3,2)</param>
<!-- <param name="l_hand">(l_hand_dh_frame,3,6)</param>
<param name="r_hand">(r_hand_dh_frame,4,6)</param> -->
<param name="l_elbow_1">(l_elbow_1, 3, 4)</param>
<param name="r_upper_arm">(r_upper_arm,4,2)</param>
<param name="r_elbow_1">(r_elbow_1, 4, 4)</param>
<param name="l_lower_leg">(l_lower_leg,5,3)</param>
<param name="l_ankle_1">(l_ankle_1,5,4)</param>
<param name="l_foot">(l_foot_dh_frame,5,5)</param>
<param name="r_foot">(r_foot_dh_frame,6,5)</param>
<param name="r_lower_leg">(r_lower_leg,6,3)</param>
<param name="r_ankle_1">(r_ankle_1,6,4)</param>
<param name="r_ankle_2">(r_foot_dh_frame,6,5)</param>
</group>

<group name="GRAVITY_COMPENSATION">
<param name="enableGravityCompensation">true</param>
<param name="gravityCompensationBaseLink">root_link</param>
<param name="gravityCompensationAxesNames">(torso_pitch,torso_roll,torso_yaw,neck_pitch,neck_roll,neck_yaw,l_shoulder_pitch,l_shoulder_roll,l_shoulder_yaw,l_elbow,r_shoulder_pitch,r_shoulder_roll,r_shoulder_yaw,r_elbow,l_hip_pitch,l_hip_roll,l_hip_yaw,l_knee,l_ankle_pitch,l_ankle_roll,r_hip_pitch,r_hip_roll,r_hip_yaw,r_knee,r_ankle_pitch,r_ankle_roll)</param>
</group>

<!-- <group name="FT_SECONDARY_CALIBRATION">
<param name="l_leg_ft_sensor">
(7.425024e-01,5.604686e-02,-4.408041e-02,3.727271e-01,6.718566e-01,2.605184e-01
,2.376318e-02,4.601413e-01,9.920935e-03,-8.951425e-01,-1.167558e-01,1.971860e+00
,-7.972684e-02,-2.326263e-01,9.977213e-01,-1.405751e+00,3.249553e-01,-1.666625e+00
,-5.519838e-03,-1.664778e-02,2.642368e-03,8.229934e-01,1.622153e-02,-2.456099e-02
,9.019424e-03,8.294730e-04,-2.194214e-03,3.696845e-03,8.865210e-01,-5.286550e-02
,1.979480e-03,1.733975e-04,-3.815689e-05,-1.993212e-02,-1.673455e-02,9.158948e-01)
</param>
<param name="r_leg_ft_sensor">
(9.308601e-01,7.328130e-03,-1.211788e-02,-1.123839e-01,-2.977943e-01,-1.954805e-02
,-8.177519e-02,7.160387e-01,-4.158542e-02,1.077732e+00,4.997348e-01,2.431916e+00
,-4.174433e-02,-1.784640e-01,9.661752e-01,-1.386611e+00,1.538259e-01,-5.603641e-01
,-1.877732e-03,-3.220898e-03,-6.874089e-04,9.546012e-01,1.329514e-02,2.982738e-02
,-2.466464e-03,2.580501e-03,-3.510048e-04,6.640786e-03,9.513549e-01,4.179682e-02
,2.002912e-03,3.654545e-04,3.323602e-04,-1.106579e-02,-8.070312e-03,9.706656e-01)
</param>
</group> -->


<group name="WBD_OUTPUT_EXTERNAL_WRENCH_PORTS">
<!-- <param name="/wholeBodyDynamics/left_arm/cartesianEndEffectorWrench:o">(l_hand,l_hand_dh_frame,root_link)</param>
<param name="/wholeBodyDynamics/right_arm/cartesianEndEffectorWrench:o">(r_hand,r_hand_dh_frame,root_link)</param> -->
<param name="/wholeBodyDynamics/left_leg/cartesianEndEffectorWrench:o">(l_lower_leg,l_lower_leg,root_link)</param>
<param name="/wholeBodyDynamics/left_foot/cartesianEndEffectorWrench:o">(l_foot,l_sole,l_sole)</param>
<param name="/wholeBodyDynamics/right_leg/cartesianEndEffectorWrench:o">(r_lower_leg,r_lower_leg,root_link)</param>
<param name="/wholeBodyDynamics/right_foot/cartesianEndEffectorWrench:o">(r_foot,r_sole,r_sole)</param>
</group>

<action phase="startup" level="15" type="attach">
<paramlist name="networks">
<!-- motorcontrol and virtual torque sensors -->
<elem name="left_lower_leg">left_leg-eb7-j4_5-mc</elem>
<elem name="right_lower_leg">right_leg-eb9-j4_5-mc</elem>
<elem name="left_upper_leg">left_leg-eb6-j0_3-mc</elem>
<elem name="right_upper_leg">right_leg-eb8-j0_3-mc</elem>
<elem name="torso">torso-eb5-j0_2-mc</elem>
<!-- <elem name="right_lower_arm">right_arm-eb27-j4_7-mc</elem>
<elem name="left_lower_arm">left_arm-eb24-j4_7-mc</elem> -->
<elem name="right_upper_arm">right_arm-eb3-j0_3-mc</elem>
<elem name="left_upper_arm">left_arm-eb1-j0_3-mc</elem>
<elem name="head-j0">head-eb20-j0_1-mc</elem>
<elem name="head-j2">head-eb21-j2_5-mc</elem>
<!-- imu -->
<elem name="imu">head-inertial</elem>
<!-- imu_waist -->
<!-- <elem name="imu">xsens_inertial</elem> -->
<!-- ft -->
<elem name="l_arm_ft_sensor">left_arm-eb1-j0_3-strain</elem>
<elem name="r_arm_ft_sensor">right_arm-eb3-j0_3-strain</elem>
<elem name="l_leg_ft_sensor">left_leg-eb6-j0_3-strain</elem>
<elem name="r_leg_ft_sensor">right_leg-eb8-j0_3-strain</elem>
<elem name="l_foot_ft_sensor">left_leg-eb7-j4_5-strain</elem>
<elem name="r_foot_ft_sensor">right_leg-eb9-j4_5-strain</elem>
</paramlist>
</action>

<action phase="shutdown" level="2" type="detach" />

</device>

124 changes: 124 additions & 0 deletions iCubGenova04/iRonCub-noLegs_wbd.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,124 @@
<?xml version="1.0" encoding="UTF-8" ?>
<!DOCTYPE robot PUBLIC "-//YARP//DTD yarprobotinterface 3.0//EN" "http://www.yarp.it/DTD/yarprobotinterfaceV3.0.dtd">

<robot name="iCubGenova04" build="1" portprefix="icub" xmlns:xi="http://www.w3.org/2001/XInclude">
<params>
<xi:include href="hardware/electronics/pc104.xml" />
</params>

<devices>
<!-- HEAD -->
<xi:include href="./hardware/motorControl/head-eb20-j0_1-mc.xml" />
<xi:include href="./hardware/motorControl/head-eb21-j2_5-mc.xml" />
<xi:include href="./wrappers/motorControl/head-mc_wrapper.xml" />

<!-- TORSO -->
<!-- <xi:include href="hardware/motorControl/torso-eb5-j0_2-mc.xml" />
<xi:include href="wrappers/motorControl/torso-mc_wrapper.xml" /> -->

<!-- LEFT ARM -->
<xi:include href="hardware/motorControl/left_arm-eb1-j0_3-mc.xml" />
<!-- <xi:include href="hardware/motorControl/left_arm-eb24-j4_7-mc.xml" />
<xi:include href="hardware/motorControl/left_arm-eb25-j8_11-mc.xml" />
<xi:include href="hardware/motorControl/left_arm-eb26-j12_15-mc.xml" /> -->
<xi:include href="wrappers/motorControl/left_arm-mc_wrapper_iRonCub.xml" />

<!-- RIGHT ARM -->
<xi:include href="hardware/motorControl/right_arm-eb3-j0_3-mc.xml" />
<!-- <xi:include href="hardware/motorControl/right_arm-eb27-j4_7-mc.xml" />
<xi:include href="hardware/motorControl/right_arm-eb28-j8_11-mc.xml" />
<xi:include href="hardware/motorControl/right_arm-eb29-j12_15-mc.xml" /> -->
<xi:include href="wrappers/motorControl/right_arm-mc_wrapper_iRonCub.xml" />

<!-- LEFT LEG -->
<!-- <xi:include href="hardware/motorControl/left_leg-eb6-j0_3-mc.xml" />
<xi:include href="hardware/motorControl/left_leg-eb7-j4_5-mc.xml" />
<xi:include href="wrappers/motorControl/left_leg-mc_wrapper.xml" /> -->

<!-- RIGHT LEG -->
<!-- <xi:include href="hardware/motorControl/right_leg-eb8-j0_3-mc.xml" />
<xi:include href="hardware/motorControl/right_leg-eb9-j4_5-mc.xml" />
<xi:include href="wrappers/motorControl/right_leg-mc_wrapper.xml" /> -->


<!-- INERTIAL SENSOR-->
<xi:include href="wrappers/inertials/head-imuFilter_wrapper.xml" />
<xi:include href="wrappers/inertials/head-imuFilter.xml" />
<xi:include href="wrappers/inertials/head-inertials_wrapper.xml" />
<xi:include href="wrappers/inertials/head-inertials_wrapper-deprecated.xml" />
<xi:include href="hardware/inertials/head-inertial.xml" />
<!-- <xi:include href="hardware/inertials/waist-inertial.xml" /> -->

<!--inertials3-->
<!-- <xi:include href="hardware/inertials/left_leg-eb7-IMU.xml" />
<xi:include href="wrappers/inertials/left_foot-imu_wrapper.xml" />
<xi:include href="hardware/inertials/right_leg-eb9-IMU.xml" />
<xi:include href="wrappers/inertials/right_foot-imu_wrapper.xml" />
<xi:include href="hardware/inertials/left_leg-eb6-IMU.xml" />
<xi:include href="wrappers/inertials/left_leg-imu_wrapper.xml" />
<xi:include href="hardware/inertials/right_leg-eb8-IMU.xml" />
<xi:include href="wrappers/inertials/right_leg-imu_wrapper.xml" /> -->

<!-- ANALOG SENSOR MAIS -->
<!-- <xi:include href="wrappers/MAIS/left_arm-mais_wrapper.xml" />
<xi:include href="wrappers/MAIS/right_arm-mais_wrapper.xml" />
<xi:include href="hardware/MAIS/left_arm-eb26-j12_15-mais.xml" />
<xi:include href="hardware/MAIS/right_arm-eb29-j12_15-mais.xml" /> -->

<!-- SKINS -->
<!-- <xi:include href="wrappers/skin/left_arm-skin_wrapper.xml" />
<xi:include href="hardware/skin/left_arm-eb24-j4_7-skin.xml" />
<xi:include href="wrappers/skin/right_arm-skin_wrapper.xml" />
<xi:include href="hardware/skin/right_arm-eb27-j4_7-skin.xml" />
<xi:include href="wrappers/skin/left_leg-skin_wrapper.xml" />
<xi:include href="hardware/skin/left_leg-eb10-skin.xml" />
<xi:include href="wrappers/skin/right_leg-skin_wrapper.xml" />
<xi:include href="hardware/skin/right_leg-eb11-skin.xml" />
<xi:include href="wrappers/skin/torso-skin_wrapper.xml" />
<xi:include href="hardware/skin/torso-eb22-skin.xml" /> -->

<!-- ANALOG SENSOR FT -->
<xi:include href="wrappers/FT/left_arm-FT_wrapper.xml" />
<xi:include href="wrappers/FT/right_arm-FT_wrapper.xml" />
<!-- <xi:include href="wrappers/FT/right_leg-FT_wrapper.xml" />
<xi:include href="wrappers/FT/left_leg-FT_wrapper.xml" />
<xi:include href="wrappers/FT/right_foot-FT_wrapper.xml" />
<xi:include href="wrappers/FT/left_foot-FT_wrapper.xml" />
<xi:include href="wrappers/FT/right_foot-FT_wrapper_multipleSens.xml" />
<xi:include href="wrappers/FT/right_leg-FT_wrapper_multipleSens.xml" />
<xi:include href="wrappers/FT/left_leg-FT_wrapper_multipleSens.xml" />
<xi:include href="wrappers/FT/left_foot-FT_wrapper_multipleSens.xml" /> -->
<xi:include href="hardware/FT/left_arm-eb1-j0_3-strain.xml" />
<xi:include href="hardware/FT/right_arm-eb3-j0_3-strain.xml" />
<!-- <xi:include href="hardware/FT/left_leg-eb6-j0_3-strain2.xml" />
<xi:include href="hardware/FT/left_leg-eb7-j4_5-strain2.xml" />
<xi:include href="hardware/FT/right_leg-eb8-j0_3-strain2.xml" />
<xi:include href="hardware/FT/right_leg-eb9-j4_5-strain2.xml" /> -->

<!-- VIRTUAL ANALOG SENSORS (WRAPPER ONLY)
<xi:include href="wrappers/VFT/left_arm-VFT_wrapper.xml" />
<xi:include href="wrappers/VFT/right_leg-VFT_wrapper.xml" />
<xi:include href="wrappers/VFT/left_leg-VFT_wrapper.xml" />
<xi:include href="wrappers/VFT/right_arm-VFT_wrapper.xml" />
<xi:include href="wrappers/VFT/torso-VFT_wrapper.xml" /> -->

<!-- CALIBRATORS -->
<xi:include href="calibrators/left_arm-calib_iRonCub.xml" />
<xi:include href="calibrators/right_arm-calib_iRonCub.xml" />
<!-- <xi:include href="calibrators/left_leg-calib.xml" />
<xi:include href="calibrators/right_leg-calib.xml" />
<xi:include href="calibrators/torso-calib.xml" /> -->
<xi:include href="calibrators/head-calib.xml" />

<!-- CARTESIANS -->
<!-- <xi:include href="cartesian/left_arm-cartesian.xml" />
<xi:include href="cartesian/right_arm-cartesian.xml" /> -->

<!-- ESTIMATORS -->
<!-- <xi:include href="estimators/wholebodydynamics_iRonCub.xml" /> -->

<!-- ROS -->
<!-- <xi:include href="wrappers/motorControl/icub_ros_wrapper.xml" /> -->

</devices>
</robot>
Loading

0 comments on commit 1a05e78

Please sign in to comment.