Commit 7d4bf844 authored by Carlos Mastalli's avatar Carlos Mastalli
Browse files

Merge branch 'topic/kinova' into 'devel'

Added the Kinova arm + ANYmal with kinova; renamed the reference postures

See merge request !18
parents 5af2f8de 6286dd38
Pipeline #6553 passed with stage
in 8 minutes and 45 seconds
*.pyc
*.pyd
*.pyo
build*
......@@ -43,6 +43,7 @@ IF(NOT INSTALL_PYTHON_INTERFACE_ONLY)
INSTALL(DIRECTORY solo_description DESTINATION share/${PROJECT_NAME})
INSTALL(DIRECTORY icub_description DESTINATION share/${PROJECT_NAME})
INSTALL(DIRECTORY talos_data DESTINATION share/${PROJECT_NAME})
INSTALL(DIRECTORY kinova_description DESTINATION share/${PROJECT_NAME})
INSTALL(DIRECTORY tiago_description DESTINATION share/${PROJECT_NAME})
INSTALL(DIRECTORY ur_description DESTINATION share/${PROJECT_NAME})
ENDIF(NOT INSTALL_PYTHON_INTERFACE_ONLY)
......
......@@ -46,7 +46,7 @@ If you have never added robotpkg as a softwares repository, please follow first
(you will need pinocchio and its Python bindings)
`python -m example_robot_data [anymal,hyq,solo,solo12,talos,talos_arm,talos_legs,tiago,tiago_no_hand,icub,ur5]`
`python -m example_robot_data [anymal,anymal_kinova,hyq,solo,solo12,talos,talos_arm,talos_legs,tiago,tiago_no_hand,icub,ur5]`
This will work from the `python` subdirectory inside this repository, or if this package has been installed on your
system.
This diff is collapsed.
<?xml version="1.0" ?>
<robot name="anymal_kinova">
<group name="lf_leg">
<joint name="LF_HAA" />
<joint name="LF_HFE" />
<joint name="LF_KFE" />
<chain base_link="base" tip_link="LF_FOOT" />
</group>
<group name="lh_leg">
<joint name="LH_HAA" />
<joint name="LH_HFE" />
<joint name="LH_KFE" />
<chain base_link="base" tip_link="LH_FOOT" />
</group>
<group name="rf_leg">
<joint name="RF_HAA" />
<joint name="RF_HFE" />
<joint name="RF_KFE" />
<chain base_link="base" tip_link="RF_FOOT" />
</group>
<group name="rh_leg">
<joint name="RH_HAA" />
<joint name="RH_HFE" />
<joint name="RH_KFE" />
<chain base_link="base" tip_link="RH_FOOT" />
</group>
<group name="arm">
<joint name="j2s6s200_joint_1" />
<joint name="j2s6s200_joint_2" />
<joint name="j2s6s200_joint_3" />
<joint name="j2s6s200_joint_4" />
<joint name="j2s6s200_joint_5" />
<joint name="j2s6s200_joint_5" />
<chain base_link="base" tip_link="j2s6s200_end_effector" />
</group>
<group name="all_legs">
<group name="lf" />
<group name="rf" />
<group name="lh" />
<group name="rh" />
</group>
<group name="all">
<group name="lf" />
<group name="rf" />
<group name="lh" />
<group name="rh" />
<group name="arm" />
</group>
<group name="r_legs">
<group name="rf" />
<group name="rh" />
</group>
<group name="l_legs">
<group name="lf" />
<group name="lh" />
</group>
<group name="f_legs">
<group name="lf" />
<group name="rf" />
</group>
<group name="h_legs">
<group name="lh" />
<group name="rh" />
</group>
<group name="ld_legs">
<group name="lf" />
<group name="rh" />
</group>
<group name="rd_legs">
<group name="rf" />
<group name="lh" />
</group>
<end_effector name="lf_foot" parent_link="LF_FOOT" group="lf_leg" />
<end_effector name="rf_foot" parent_link="RF_FOOT" group="rf_leg" />
<end_effector name="lh_foot" parent_link="LH_FOOT" group="lh_leg" />
<end_effector name="rh_foot" parent_link="RH_FOOT" group="rh_leg" />
<end_effector name="arm" parent_link="j2s6s200_end_effector" group="arm" />
<group_state name="standing_with_arm_up" group="all">
<joint name="root_joint" value="0. 0. 0.4792 0. 0. 0. 1." />
<joint name="LF_HAA" value="-0.1" />
<joint name="LF_HFE" value="0.7" />
<joint name="LF_KFE" value="-1." />
<joint name="RF_HAA" value="0.1" />
<joint name="RF_HFE" value="0.7" />
<joint name="RF_KFE" value="-1." />
<joint name="LH_HAA" value="-0.1" />
<joint name="LH_HFE" value="-0.7" />
<joint name="LH_KFE" value="1." />
<joint name="RH_HAA" value="0.1" />
<joint name="RH_HFE" value="-0.7" />
<joint name="RH_KFE" value="1." />
<joint name="j2s6s200_joint_1" value="1.5707" />
<joint name="j2s6s200_joint_2" value="2.618" />
<joint name="j2s6s200_joint_3" value="-1.5707" />
<joint name="j2s6s200_joint_4" value="3.1415" />
<joint name="j2s6s200_joint_5" value="2.618" />
<joint name="j2s6s200_joint_6" value="0." />
</group_state>
<disable_collisions link1="LF_HIP" link2="LF_THIGH" reason="Adjacent" />
<disable_collisions link1="LF_HIP" link2="LF_SHANK" reason="Never" />
<disable_collisions link1="LF_HIP" link2="LF_FOOT" reason="Never" />
<disable_collisions link1="LF_HIP" link2="RF_HIP" reason="Never" />
<disable_collisions link1="LF_HIP" link2="RF_THIGH" reason="Never" />
<disable_collisions link1="LF_HIP" link2="RF_SHANK" reason="Never" />
<disable_collisions link1="LF_HIP" link2="RF_FOOT" reason="Never" />
<disable_collisions link1="LF_HIP" link2="LH_HIP" reason="Never" />
<disable_collisions link1="LF_HIP" link2="LH_THIGH" reason="Never" />
<disable_collisions link1="LF_HIP" link2="LH_SHANK" reason="Never" />
<disable_collisions link1="LF_HIP" link2="LH_FOOT" reason="Never" />
<disable_collisions link1="LF_HIP" link2="RH_HIP" reason="Never" />
<disable_collisions link1="LF_HIP" link2="RH_THIGH" reason="Never" />
<disable_collisions link1="LF_HIP" link2="RH_SHANK" reason="Never" />
<disable_collisions link1="LF_HIP" link2="RH_FOOT" reason="Never" />
<disable_collisions link1="base" link2="LF_HIP" reason="Adjacent" />
<disable_collisions link1="base" link2="LH_HIP" reason="Adjacent" />
<disable_collisions link1="base" link2="RF_HIP" reason="Adjacent" />
<disable_collisions link1="base" link2="RH_HIP" reason="Adjacent" />
<disable_collisions link1="LF_HIP" link2="LF_THIGH" reason="Adjacent" />
<disable_collisions link1="LH_HIP" link2="LH_THIGH" reason="Adjacent" />
<disable_collisions link1="RF_HIP" link2="RF_THIGH" reason="Adjacent" />
<disable_collisions link1="RH_HIP" link2="RH_THIGH" reason="Adjacent" />
<disable_collisions link1="LF_THIGH" link2="LF_SHANK" reason="Adjacent" />
<disable_collisions link1="LH_THIGH" link2="LH_SHANK" reason="Adjacent" />
<disable_collisions link1="RF_THIGH" link2="RF_SHANK" reason="Adjacent" />
<disable_collisions link1="RH_THIGH" link2="RH_SHANK" reason="Adjacent" />
<disable_collisions link1="LF_SHANK" link2="LF_FOOT" reason="Adjacent" />
<disable_collisions link1="LH_SHANK" link2="LH_FOOT" reason="Adjacent" />
<disable_collisions link1="RF_SHANK" link2="RF_FOOT" reason="Adjacent" />
<disable_collisions link1="RH_SHANK" link2="RH_FOOT" reason="Adjacent" />
<disable_collisions link1="LF_ADAPTER" link2="LF_FOOT" reason="Adjacent" />
<disable_collisions link1="LH_ADAPTER" link2="LH_FOOT" reason="Adjacent" />
<disable_collisions link1="RF_ADAPTER" link2="RF_FOOT" reason="Adjacent" />
<disable_collisions link1="RH_ADAPTER" link2="RH_FOOT" reason="Adjacent" />
<disable_collisions link1="LF_ADAPTER" link2="LF_SHANK" reason="Adjacent" />
<disable_collisions link1="LH_ADAPTER" link2="LH_SHANK" reason="Adjacent" />
<disable_collisions link1="RF_ADAPTER" link2="RF_SHANK" reason="Adjacent" />
<disable_collisions link1="RH_ADAPTER" link2="RH_SHANK" reason="Adjacent" />
<disable_collisions link1="base" link2="imu_link" reason="Adjacent" />
<!-- Need to check these 4 ? there may be auto-collisions ... -->
<disable_collisions link1="base" link2="LF_THIGH" reason="Adjacent" />
<disable_collisions link1="base" link2="LH_THIGH" reason="Adjacent" />
<disable_collisions link1="base" link2="RF_THIGH" reason="Adjacent" />
<disable_collisions link1="base" link2="RH_THIGH" reason="Adjacent" />
</robot>
......@@ -61,7 +61,7 @@
<end_effector name="lh_foot" parent_link="LH_FOOT" group="lh_leg" />
<end_effector name="rh_foot" parent_link="RH_FOOT" group="rh_leg" />
<group_state name="half_sitting" group="all_legs">
<group_state name="standing" group="all_legs">
<joint name="root_joint" value="0. 0. 0.4792 0. 0. 0. 1." />
<joint name="LF_HAA" value="-0.1" />
<joint name="LF_HFE" value="0.7" />
......
......@@ -65,7 +65,7 @@
<end_effector name="lh_foot" parent_link="lh_foot" group="lh_leg" />
<end_effector name="rh_foot" parent_link="rh_foot" group="rh_leg" />
<group_state name="half_sitting" group="all_legs">
<group_state name="standing" group="all_legs">
<joint name="root_joint" value="0. 0. 0.5775 0. 0. 0. 1." />
<joint name="lf_haa_joint" value="-0.2" />
<joint name="lf_hfe_joint" value="0.75" />
......@@ -81,7 +81,7 @@
<joint name="rh_kfe_joint" value="1.5" />
</group_state>
<group_state name="standing" group="all_legs">
<group_state name="straight_standing" group="all_legs">
<joint name="root_joint" value="0. 0. 0.5775 0. 0. 0. 1." />
<joint name="lf_haa_joint" value="0." />
<joint name="lf_hfe_joint" value="0.75" />
......
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
Markdown is supported
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment