diff --git a/talos_controller_configuration/config/walk_poses.yaml b/talos_controller_configuration/config/walk_poses.yaml deleted file mode 100644 index 52efc0cc91be47c1fb84e85a6e3de7627492470f..0000000000000000000000000000000000000000 --- a/talos_controller_configuration/config/walk_poses.yaml +++ /dev/null @@ -1,41 +0,0 @@ -# Controller to use to move arms while walking. They must expose a FollowJointTrajectory action interface -walk_pose: - controllers: - - right_arm_controller - - left_arm_controller - - head_controller - - torso_controller - - joints_rest_pos: - - arm_left_1_joint : 0.34 - - arm_left_2_joint : 0.15 - - arm_left_3_joint : -0.34 - - arm_left_4_joint : -1.0 - - arm_left_5_joint : 0.0 - - arm_left_6_joint : 0.0 - - arm_left_7_joint : 0.0 - - - arm_right_1_joint: -0.34 - - arm_right_2_joint: -0.15 - - arm_right_3_joint: 0.34 - - arm_right_4_joint: -1.0 - - arm_right_5_joint: 0.0 - - arm_right_6_joint: 0.0 - - arm_right_7_joint: 0.0 - - - torso_1_joint: 0.0 - - torso_2_joint: 0.0 - - - head_1_joint: 0.0 - - head_2_joint: 0.0 - - joints_to_move: - - arm_left_1_joint: -1.0 - - arm_left_3_joint: 1.0 - - arm_left_4_joint: 1.0 - - arm_right_1_joint: -1.0 - - arm_right_3_joint: 1.0 - - arm_right_4_joint: 1.0 - - torso_1_joint: 0.5 - - head_2_joint: 0.5 - diff --git a/talos_description/config/joint_limits.yaml b/talos_description/config/joint_limits.yaml index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0c73ba38cb316861611d393036c595ba297b006f 100644 --- a/talos_description/config/joint_limits.yaml +++ b/talos_description/config/joint_limits.yaml @@ -0,0 +1,61 @@ +joint_limits: + torso_1_joint: + has_velocity_limits: true + max_velocity: &max_torso_vel 1.0 + torso_2_joint: + has_velocity_limits: true + max_velocity: *max_torso_vel + + head_1_joint: + has_velocity_limits: true + max_velocity: &max_head_vel 3.0 + head_2_joint: + has_velocity_limits: true + max_velocity: *max_head_vel + + arm_right_1_joint: + has_velocity_limits: true + max_velocity: &max_arm_vel 1.5 + arm_right_2_joint: + has_velocity_limits: true + max_velocity: *max_arm_vel + arm_right_3_joint: + has_velocity_limits: true + max_velocity: *max_arm_vel + arm_right_4_joint: + has_velocity_limits: true + max_velocity: *max_arm_vel + arm_right_5_joint: + has_velocity_limits: true + max_velocity: *max_arm_vel + arm_right_6_joint: + has_velocity_limits: true + max_velocity: *max_arm_vel + arm_right_7_joint: + has_velocity_limits: true + max_velocity: *max_arm_vel + + arm_left_1_joint: + has_velocity_limits: true + max_velocity: *max_arm_vel + arm_left_2_joint: + has_velocity_limits: true + max_velocity: *max_arm_vel + arm_left_3_joint: + has_velocity_limits: true + max_velocity: *max_arm_vel + arm_left_4_joint: + has_velocity_limits: true + max_velocity: *max_arm_vel + arm_left_5_joint: + has_velocity_limits: true + max_velocity: *max_arm_vel + arm_left_6_joint: + has_velocity_limits: true + max_velocity: *max_arm_vel + arm_left_7_joint: + has_velocity_limits: true + max_velocity: *max_arm_vel + + # Hands and legs keep the default values from URDF + diff --git a/talos_description/robots/talos_arm.urdf.xacro b/talos_description/robots/talos_arm.urdf.xacro index dcf152cab4c2e57565d668442b7c65ac1a9cc780..8009a758e9ba5955d1b43768fd8e55118c60a0da 100644 --- a/talos_description/robots/talos_arm.urdf.xacro +++ b/talos_description/robots/talos_arm.urdf.xacro @@ -14,7 +14,7 @@ xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"> <xacro:include filename="$(find talos_description)/urdf/arm/arm.urdf.xacro" /> - <xacro:include filename="$(find talos_description)/urdf/gripper/gripper_v2.urdf.xacro" /> + <xacro:include filename="$(find talos_description)/urdf/gripper/gripper.urdf.xacro" /> <link name="talos_2_link"> <inertial> diff --git a/talos_description/robots/talos_full.urdf.xacro b/talos_description/robots/talos_full.urdf.xacro index 1256b2c5f230525b28ecf5f3f72e0d083132313f..c2a3d80b6f050bcad740f7163bf7bd28eebeb8a0 100644 --- a/talos_description/robots/talos_full.urdf.xacro +++ b/talos_description/robots/talos_full.urdf.xacro @@ -17,8 +17,8 @@ <xacro:include filename="$(find talos_description)/urdf/head/head.urdf.xacro" /> <xacro:include filename="$(find talos_description)/urdf/arm/arm.urdf.xacro" /> <xacro:include filename="$(find talos_description)/urdf/sensors/ftsensor.urdf.xacro" /> - <xacro:include filename="$(find talos_description)/urdf/gripper/gripper_v2.urdf.xacro" /> - <xacro:include filename="$(find talos_description)/urdf/leg/leg_v2.urdf.xacro" /> + <xacro:include filename="$(find talos_description)/urdf/gripper/gripper.urdf.xacro" /> + <xacro:include filename="$(find talos_description)/urdf/leg/leg.urdf.xacro" /> <xacro:talos_torso name="torso" /> diff --git a/talos_description/robots/talos_full_no_grippers.urdf.xacro b/talos_description/robots/talos_full_no_grippers.urdf.xacro index 9cfdb294df0354e3022c125a744be76fc04013ff..34000bdfd4af46206b31b08809280f91143ffa93 100644 --- a/talos_description/robots/talos_full_no_grippers.urdf.xacro +++ b/talos_description/robots/talos_full_no_grippers.urdf.xacro @@ -17,8 +17,7 @@ <xacro:include filename="$(find talos_description)/urdf/head/head.urdf.xacro" /> <xacro:include filename="$(find talos_description)/urdf/arm/arm.urdf.xacro" /> <xacro:include filename="$(find talos_description)/urdf/sensors/ftsensor.urdf.xacro" /> - <xacro:include filename="$(find talos_description)/urdf/gripper/gripper_v2.urdf.xacro" /> - <xacro:include filename="$(find talos_description)/urdf/leg/leg_v2.urdf.xacro" /> + <xacro:include filename="$(find talos_description)/urdf/leg/leg.urdf.xacro" /> <xacro:talos_torso name="torso" /> diff --git a/talos_description/robots/talos_full_no_lower_arm.urdf.xacro b/talos_description/robots/talos_full_no_lower_arm.urdf.xacro index 5002543e444d00f178c22d44b40be2754236d2ba..d1b8836bb8a0986902ac09096bb5c2d53fc53241 100644 --- a/talos_description/robots/talos_full_no_lower_arm.urdf.xacro +++ b/talos_description/robots/talos_full_no_lower_arm.urdf.xacro @@ -17,8 +17,8 @@ <xacro:include filename="$(find talos_description)/urdf/head/head.urdf.xacro" /> <xacro:include filename="$(find talos_description)/urdf/arm/arm.urdf.xacro" /> <xacro:include filename="$(find talos_description)/urdf/sensors/ftsensor.urdf.xacro" /> - <xacro:include filename="$(find talos_description)/urdf/gripper/gripper_v2.urdf.xacro" /> - <xacro:include filename="$(find talos_description)/urdf/leg/leg_v2.urdf.xacro" /> + <xacro:include filename="$(find talos_description)/urdf/gripper/gripper.urdf.xacro" /> + <xacro:include filename="$(find talos_description)/urdf/leg/leg.urdf.xacro" /> <xacro:talos_torso name="torso" /> diff --git a/talos_description/robots/talos_gripper.urdf.xacro b/talos_description/robots/talos_gripper.urdf.xacro index 897316815a9a8054983b4aea352146b03756c00a..7f48aa9c4484182cbade85da9315784a08791ed3 100644 --- a/talos_description/robots/talos_gripper.urdf.xacro +++ b/talos_description/robots/talos_gripper.urdf.xacro @@ -13,7 +13,7 @@ xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller" xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"> - <xacro:include filename="$(find talos_description)/urdf/gripper/gripper_v2.urdf.xacro" /> + <xacro:include filename="$(find talos_description)/urdf/gripper/gripper.urdf.xacro" /> <xacro:include filename="$(find talos_description)/urdf/torso/torso.urdf.xacro" /> diff --git a/talos_description/robots/talos_lower_body.urdf.xacro b/talos_description/robots/talos_lower_body.urdf.xacro index c4792a9a6047e5c5ec9adb3a8b127b9c71f132f3..0c7f876c770d8c5c711bfe7dedce618be258e521 100644 --- a/talos_description/robots/talos_lower_body.urdf.xacro +++ b/talos_description/robots/talos_lower_body.urdf.xacro @@ -1,7 +1,7 @@ <?xml version="1.0"?> <!-- - Copyright (c) 2016, PAL Robotics, S.L. + Copyright (c) 2014, PAL Robotics, S.L. All rights reserved. This work is licensed under the Creative Commons Attribution-NonCommercial-NoDerivs 3.0 Unported License. @@ -13,17 +13,7 @@ xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller" xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"> - <xacro:include filename="$(find talos_description)/urdf/torso/torso.urdf.xacro" /> - <xacro:include filename="$(find talos_description)/urdf/head/head.urdf.xacro" /> - <xacro:include filename="$(find talos_description)/urdf/arm/arm.urdf.xacro" /> - <xacro:include filename="$(find talos_description)/urdf/sensors/ftsensor.urdf.xacro" /> - <xacro:include filename="$(find talos_description)/urdf/gripper/gripper_v2.urdf.xacro" /> - <xacro:include filename="$(find talos_description)/urdf/leg/leg_v2.urdf.xacro" /> - - - <!--************************--> - <!-- BASE_LINK --> - <!--************************--> + <xacro:include filename="$(find talos_description)/urdf/leg/leg.urdf.xacro" /> <link name="base_link"> <inertial> <origin xyz="-0.08222 0.00838 -0.07261" rpy="0.00000 0.00000 0.00000"/> @@ -34,35 +24,28 @@ </inertial> <visual> - <origin xyz="0 0 0" rpy="0 0 0" /> + <origin rpy="0 0 0" xyz="0 0 0"/> <geometry> - <mesh filename="package://talos_description/meshes/torso/base_link.STL" scale="1 1 1"/> + <mesh filename="package://talos_description/meshes/talos/base_link.STL" scale="1 1 1"/> </geometry> - <material name="LightGrey" /> + <material name="DarkGrey" /> </visual> - + <collision> - <origin xyz="0 0 0" rpy="0 0 0" /> + <origin rpy="0 0 0" xyz="0 0 0"/> <geometry> - <mesh filename="package://talos_description/meshes/torso/base_link_collision.STL" scale="1 1 1"/> + <mesh filename="package://talos_description/meshes/talos/base_link_collision.STL" scale="1 1 1"/> </geometry> - </collision> + </collision> </link> - - <xacro:talos_leg prefix="left" reflect="1" /> - <xacro:talos_leg prefix="right" reflect="-1" /> + + + <xacro:talos_leg prefix="left" reflect="1" /> + <xacro:talos_leg prefix="right" reflect="-1" /> <!-- Generic simulatalos_gazebo plugins --> <xacro:include filename="$(find talos_description)/gazebo/gazebo.urdf.xacro" /> <!-- Materials for visualization --> <xacro:include filename="$(find talos_description)/urdf/materials.urdf.xacro" /> - - <xacro:include filename="$(find talos_description)/urdf/sensors/imu.urdf.xacro" /> - - <!-- imu --> - <xacro:talos_imu name="imu" parent="base_link" update_rate="100.0"> - <origin xyz="0 0 0" rpy="0 0 0"/> - </xacro:talos_imu> - </robot> diff --git a/talos_description/robots/talos_lower_body_v1.urdf.xacro b/talos_description/robots/talos_lower_body_v1.urdf.xacro deleted file mode 100644 index b9d86aff6d2dcf9493f636683859cbbef957ec01..0000000000000000000000000000000000000000 --- a/talos_description/robots/talos_lower_body_v1.urdf.xacro +++ /dev/null @@ -1,59 +0,0 @@ -<?xml version="1.0"?> -<!-- - - Copyright (c) 2014, PAL Robotics, S.L. - All rights reserved. - - This work is licensed under the Creative Commons Attribution-NonCommercial-NoDerivs 3.0 Unported License. - To view a copy of this license, visit http://creativecommons.org/licenses/by-nc-nd/3.0/ or send a letter to - Creative Commons, 444 Castro Street, Suite 900, Mountain View, California, 94041, USA. ---> -<robot name="talos" xmlns:xacro="http://ros.org/wiki/xacro" - xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor" - xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller" - xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"> - - - <xacro:include filename="$(find talos_description)/urdf/leg/leg.urdf.xacro" /> - - <link name="base_link"> - <inertial> - <origin xyz="0.0 0.0 0.36" rpy="0 0 0"/> - <mass value="34.0" /> - <inertia ixx="0.529688470" ixy="0.0" ixz="0.0" iyy="0.34860507904" iyz="0.0" izz="0.23865908621" /> - </inertial> - - <visual> - <origin rpy="0 0 0" xyz="0 0 0"/> - <geometry> - <mesh filename="package://talos_description/meshes/talos_dummy.stl" scale="1 1 1"/> - </geometry> - </visual> - - <collision> - <origin rpy="0 0 0" xyz="0 0 0.05"/> - <geometry> - <box size="0.1 0.3 0.1"/> - </geometry> - </collision> - - </link> - - - <xacro:talos_leg prefix="left" reflect="1" /> - <xacro:talos_leg prefix="right" reflect="-1" /> - - <!-- Generic simulatalos_gazebo plugins --> - <xacro:include filename="$(find talos_description)/gazebo/gazebo.urdf.xacro" /> - <!-- Materials for visualization --> - <xacro:include filename="$(find talos_description)/urdf/materials.urdf.xacro" /> - - - <xacro:include filename="$(find talos_description)/urdf/sensors/imu.urdf.xacro" /> - - <!-- imu --> - <xacro:talos_imu name="imu" parent="base_link" update_rate="100.0"> - <origin xyz="0 0 0" rpy="0 0 0"/> - </xacro:talos_imu> - -</robot> diff --git a/talos_description/robots/talos_lower_body_v2.urdf.xacro b/talos_description/robots/talos_lower_body_v2.urdf.xacro deleted file mode 100644 index 101bed5410e089b35aac1a9fc1d85de1ef93f7e4..0000000000000000000000000000000000000000 --- a/talos_description/robots/talos_lower_body_v2.urdf.xacro +++ /dev/null @@ -1,51 +0,0 @@ -<?xml version="1.0"?> -<!-- - - Copyright (c) 2014, PAL Robotics, S.L. - All rights reserved. - - This work is licensed under the Creative Commons Attribution-NonCommercial-NoDerivs 3.0 Unported License. - To view a copy of this license, visit http://creativecommons.org/licenses/by-nc-nd/3.0/ or send a letter to - Creative Commons, 444 Castro Street, Suite 900, Mountain View, California, 94041, USA. ---> -<robot name="talos" xmlns:xacro="http://ros.org/wiki/xacro" - xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor" - xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller" - xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"> - - <xacro:include filename="$(find talos_description)/urdf/leg/leg_v2.urdf.xacro" /> - <link name="base_link"> - <inertial> - <origin xyz="-0.08222 0.00838 -0.07261" rpy="0.00000 0.00000 0.00000"/> - <mass value="13.53810"/> - <inertia ixx="0.06989000000" ixy="-0.00011700000" ixz="0.00023000000" - iyy="0.03998200000" iyz="-0.00132500000" - izz="0.08234500000"/> - </inertial> - - <visual> - <origin rpy="0 0 0" xyz="0 0 0"/> - <geometry> - <mesh filename="package://talos_description/meshes/talos/base_link.STL" scale="1 1 1"/> - </geometry> - <material name="DarkGrey" /> - </visual> - - <collision> - <origin rpy="0 0 0" xyz="0 0 0"/> - <geometry> - <mesh filename="package://talos_description/meshes/talos/base_link_collision.STL" scale="1 1 1"/> - </geometry> - </collision> - </link> - - - <xacro:talos_leg prefix="left" reflect="1" /> - <xacro:talos_leg prefix="right" reflect="-1" /> - - <!-- Generic simulatalos_gazebo plugins --> - <xacro:include filename="$(find talos_description)/gazebo/gazebo.urdf.xacro" /> - <!-- Materials for visualization --> - <xacro:include filename="$(find talos_description)/urdf/materials.urdf.xacro" /> - -</robot> diff --git a/talos_description/robots/talos_lower_body_with_torso.urdf.xacro b/talos_description/robots/talos_lower_body_with_torso.urdf.xacro index 423e0e27c4c102da84b03f8e2838bea95996462d..4226ffb1493bcaf86a66a1df7f5cde98af422096 100644 --- a/talos_description/robots/talos_lower_body_with_torso.urdf.xacro +++ b/talos_description/robots/talos_lower_body_with_torso.urdf.xacro @@ -17,8 +17,8 @@ <xacro:include filename="$(find talos_description)/urdf/head/head.urdf.xacro" /> <xacro:include filename="$(find talos_description)/urdf/arm/arm.urdf.xacro" /> <xacro:include filename="$(find talos_description)/urdf/sensors/ftsensor.urdf.xacro" /> - <xacro:include filename="$(find talos_description)/urdf/gripper/gripper_v2.urdf.xacro" /> - <xacro:include filename="$(find talos_description)/urdf/leg/leg_v2.urdf.xacro" /> + <xacro:include filename="$(find talos_description)/urdf/gripper/gripper.urdf.xacro" /> + <xacro:include filename="$(find talos_description)/urdf/leg/leg.urdf.xacro" /> <xacro:talos_torso name="torso" /> diff --git a/talos_description/robots/upload_legs.launch b/talos_description/robots/upload_legs.launch index ef7fcf79cd706f65c142d9a0dad26293c36378dd..d05d5afbbab1901fce267df021bbdeaf7780f071 100644 --- a/talos_description/robots/upload_legs.launch +++ b/talos_description/robots/upload_legs.launch @@ -1,7 +1,5 @@ <launch> - <arg name="robot" default="titanium"/> - <!-- Robot description --> <param name="robot_description" command="$(find xacro)/xacro.py '$(find talos_description)/robots/talos_lower_body.urdf.xacro'" /> diff --git a/talos_description/robots/upload_legs_v2.launch b/talos_description/robots/upload_legs_v2.launch deleted file mode 100644 index b554fd58360bc283bb6aeffffc9a5aa393523226..0000000000000000000000000000000000000000 --- a/talos_description/robots/upload_legs_v2.launch +++ /dev/null @@ -1,8 +0,0 @@ -<launch> - - <arg name="robot" default="titanium"/> - - <!-- Robot description --> - <param name="robot_description" command="$(find xacro)/xacro.py '$(find talos_description)/robots/talos_lower_body_v2.urdf.xacro'" /> - -</launch> diff --git a/talos_description/urdf/gripper/gripper.urdf.xacro b/talos_description/urdf/gripper/gripper.urdf.xacro index 30999e2fb5d063340e85463f33d0a48be9501022..c1cd6c0ff2f96a1397cdfcee439c152791087bcb 100644 --- a/talos_description/urdf/gripper/gripper.urdf.xacro +++ b/talos_description/urdf/gripper/gripper.urdf.xacro @@ -3,74 +3,318 @@ <robot xmlns:xacro="http://ros.org/wiki/xacro"> <!--File includes--> - <!-- <xacro:include filename="$(find talos_description)/urdf/deg_to_rad.urdf.xacro" /> - <xacro:include filename="$(find talos_description)/urdf/gripper.transmission.xacro" /> - <xacro:include filename="$(find talos_description)/urdf/gripper.gazebo.xacro" /> --> - - - <xacro:macro name="talos_gripper" params="name parent"> - - <link name="${name}_base_link"> - <inertial> - <origin xyz="0.01507 -0.01177 -0.02788" rpy="0.00000 0.00000 0.00000"/> - <mass value="0.66262"/> - <inertia ixx="0.00195600000" ixy="-0.00007300000" ixz="0.00026500000" - iyy="0.00139500000" iyz="-0.00015700000" - izz="0.00170400000"/> - </inertial> - <visual> - <origin rpy="0 0 0" xyz="0 0 0" /> - <geometry> - <mesh filename="package://talos_description/meshes/gripper/base_link.STL"/> - </geometry> - <material name="DarkGrey"/> - </visual> - <collision> - <origin rpy="0 0 0" xyz="0 0 0" /> - <geometry> - <mesh filename="package://talos_description/meshes/gripper/base_link_collision.STL"/> - </geometry> - </collision> - </link> - - <joint name="${name}_base_joint" type="fixed"> - <parent link="${parent}" /> - <child link="${name}_base_link" /> - <axis xyz="0 0 0" /> - <origin xyz="0 0 0" rpy="0 0 0" /> - </joint> - - <link name="${name}_link"> - <inertial> - <origin xyz="0.01507 -0.01177 -0.02788" rpy="0.00000 0.00000 0.00000"/> - <mass value="0.3"/> - <inertia ixx="0.00195600000" ixy="-0.00007300000" ixz="0.00026500000" - iyy="0.00139500000" iyz="-0.00015700000" - izz="0.00170400000"/> - </inertial> - <visual> - <origin rpy="0 0 0" xyz="0 0 0" /> - <geometry> - <mesh filename="package://talos_description/meshes/gripper/gripper_simple.STL"/> - </geometry> - <material name="Orange"/> - </visual> - <collision> - <origin rpy="0 0 0" xyz="0 0 0" /> - <geometry> - <mesh filename="package://talos_description/meshes/gripper/gripper_simple_collision.STL"/> - </geometry> - </collision> - </link> - - <joint name="${name}_joint" type="fixed"> - <parent link="${name}_base_link" /> - <child link="${name}_link" /> - <axis xyz="0 0 0" /> - <origin xyz="0 0.02025 -0.02875" rpy="0 0 0" /> - </joint> + <xacro:include filename="$(find talos_description)/urdf/deg_to_rad.xacro" /> + <xacro:include filename="$(find talos_description)/urdf/gripper/gripper.transmission.xacro" /> + <xacro:include filename="$(find talos_description)/urdf/gripper/gripper.gazebo.xacro" /> + <xacro:macro name="talos_gripper" params="name parent reflect"> + + <link name="${name}_base_link"> + <inertial> + <origin xyz="-0.00534 0.00362 -0.02357" rpy="0.00000 0.00000 0.00000"/> + <mass value="0.61585"/> + <inertia ixx="0.00047200000" ixy="-0.00000800000" ixz="0.00003500000" + iyy="0.00052100000" iyz="0.00000000000" + izz="0.00069000000"/> + </inertial> + + <visual> + <origin xyz="0 0 0" rpy="0 0 0" /> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/base_link.STL" scale="1 1 1"/> + </geometry> + <material name="DarkGrey"/> + </visual> + + <collision> + <origin xyz="0 0 0" rpy="0 0 0" /> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/base_link_collision.STL" scale="1 1 1"/> + </geometry> + </collision> + </link> + + <joint name="${name}_base_link_joint" type="fixed"> + <parent link="${parent}"/> + <child link="${name}_base_link"/> + <origin xyz="0.00000 0.00000 -0.02875" + rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/> + <axis xyz="0 0 0" /> + </joint> + + + <link name="${name}_motor_double_link"> + <inertial> + <origin xyz="0.02270 0.01781 -0.00977" rpy="0.00000 0.00000 0.00000"/> + <mass value="0.16889"/> + <!-- In order for Gazebo not to explode we needed to add these 0.001 values to the diagonal, + also the tool pal_dynamics InertiaMassVisualization gave NaN on the computation of the inertia box --> + <inertia ixx="${0.00015900000 + 0.001}" ixy="-0.00007000000" ixz="0.00003800000" + iyy="${0.00022100000 + 0.001}" iyz="-0.00005300000" + izz="${0.00026800000 + 0.001}"/> + </inertial> + + <visual> + <origin xyz="0 0 0" rpy="0 0 0" /> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/gripper_motor_double.STL" scale="1 1 1"/> + </geometry> + <material name="Orange"/> + </visual> + + <collision> + <origin xyz="0 0 0" rpy="0 0 0" /> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/gripper_motor_double_collision.STL" scale="1 1 1"/> + </geometry> + </collision> + </link> + + <joint name="${name}_joint" type="revolute"> + <parent link="${name}_base_link"/> + <child link="${name}_motor_double_link"/> + <origin xyz="0.0 0.02025 -0.03" + rpy="${0.0 * deg_to_rad} ${0.0 * deg_to_rad} ${0.0 * deg_to_rad}"/> + <axis xyz="1 0 0" /> + <limit lower="${-60.0 * deg_to_rad}" upper="${0.0 * deg_to_rad}" effort="1.0" velocity="1.0" /> + <dynamics friction="1.0" damping="1.0"/> + </joint> + + + <link name="${name}_inner_double_link"> + <inertial> + <origin xyz="-0.00056 0.03358 -0.01741" rpy="0.00000 0.00000 0.00000"/> + <mass value="0.11922"/> + <inertia ixx="0.00009100000" ixy="0.00000100000" ixz="-0.00000100000" + iyy="0.00015600000" iyz="-0.00003200000" + izz="0.00012600000"/> + </inertial> + + <visual> + <origin xyz="0 0 0" rpy="0 0 0" /> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/inner_double.STL" scale="1 1 1"/> + </geometry> + <material name="Orange"/> + </visual> + + <collision> + <origin xyz="0 0 0" rpy="0 0 0" /> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/inner_double_collision.STL" scale="1 1 1"/> + </geometry> + </collision> + </link> + + <joint name="${name}_inner_double_joint" type="revolute"> + <parent link="${name}_base_link"/> + <child link="${name}_inner_double_link"/> + <origin xyz="0.00000 0.00525 -0.05598" + rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/> + <axis xyz="1 0 0" /> + <limit lower="${-60.0 * deg_to_rad}" upper="${0.0 * deg_to_rad}" effort="100.0" velocity="1.0" /> + <mimic joint="${name}_joint" multiplier="${1.0}" offset="0.0" /> + + </joint> + + + + <link name="${name}_fingertip_1_link"> + <inertial> + <origin xyz="0.00000 0.00460 -0.00254" rpy="0.00000 0.00000 0.00000"/> + <mass value="0.02630"/> + <inertia ixx="0.00000800000" ixy="0.00000000000" ixz="0.00000000000" + iyy="0.00000900000" iyz="0.00000100000" + izz="0.00000200000"/> + </inertial> + + <visual> + <origin xyz="0 0 0" rpy="0 0 0" /> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/fingertip.STL" scale="1 1 1"/> + </geometry> + <material name="DarkGrey"/> + </visual> + + <collision> + <origin xyz="0 0 0" rpy="0 0 0" /> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/fingertip_collision.STL" scale="1 1 1"/> + </geometry> + </collision> + </link> + + + <joint name="${name}_fingertip_1_joint" type="revolute"> + <parent link="${name}_inner_double_link"/> + <child link="${name}_fingertip_1_link"/> + <origin xyz="0.03200 0.04589 -0.06553" + rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/> + <axis xyz="1 0 0" /> + <limit lower="${0.0 * deg_to_rad}" upper="${60.0 * deg_to_rad}" effort="100.0" velocity="1.0" /> + <mimic joint="${name}_joint" multiplier="${-1.0}" offset="0.0" /> + </joint> + + + <link name="${name}_fingertip_2_link"> + <inertial> + <origin xyz="0.00000 0.00460 -0.00254" rpy="0.00000 0.00000 0.00000"/> + <mass value="0.02630"/> + <inertia ixx="0.00000800000" ixy="0.00000000000" ixz="0.00000000000" + iyy="0.00000900000" iyz="0.00000100000" + izz="0.00000200000"/> + </inertial> + + <visual> + <origin xyz="0 0 0" rpy="0 0 0" /> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/fingertip.STL" scale="1 1 1"/> + </geometry> + <material name="DarkGrey"/> + </visual> + + <collision> + <origin xyz="0 0 0" rpy="0 0 0" /> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/fingertip_collision.STL" scale="1 1 1"/> + </geometry> + </collision> + </link> + + <joint name="${name}_fingertip_2_joint" type="revolute"> + <parent link="${name}_inner_double_link"/> + <child link="${name}_fingertip_2_link"/> + <origin xyz="-0.03200 0.04589 -0.06553" + rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/> + <axis xyz="1 0 0" /> + <limit lower="${0.0 * deg_to_rad}" upper="${60.0 * deg_to_rad}" effort="100.0" velocity="1.0" /> + <mimic joint="${name}_joint" multiplier="${-1.0}" offset="0.0" /> + </joint> + + + <link name="${name}_motor_single_link"> + <inertial> + <origin xyz="0.02589 -0.01284 -0.00640" rpy="0.00000 0.00000 0.00000"/> + <mass value="0.14765"/> + <inertia ixx="0.00011500000" ixy="0.00005200000" ixz="0.00002500000" + iyy="0.00015300000" iyz="0.00003400000" + izz="0.00019000000"/> + </inertial> + + <visual> + <origin xyz="0 0 0" rpy="0 0 0" /> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/gripper_motor_single.STL" scale="1 1 1"/> + </geometry> + <material name="Orange"/> + </visual> + + <collision> + <origin xyz="0 0 0" rpy="0 0 0" /> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/gripper_motor_single_collision.STL" scale="1 1 1"/> + </geometry> + </collision> + </link> + + <joint name="${name}_motor_single_joint" type="revolute"> + <parent link="${name}_base_link"/> + <child link="${name}_motor_single_link"/> + <origin xyz="0.00000 -0.02025 -0.03000" + rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/> + <axis xyz="1 0 0" /> + <limit lower="${0.0 * deg_to_rad}" upper="${60.0 * deg_to_rad}" effort="100.0" velocity="1.0" /> + <mimic joint="${name}_joint" multiplier="${-1.0}" offset="0.0" /> + </joint> + + + + <link name="${name}_inner_single_link"> + <inertial> + <origin xyz="0.00000 -0.03253 -0.01883" rpy="0.00000 0.00000 0.00000"/> + <mass value="0.05356"/> + <inertia ixx="0.00004700000" ixy="-0.00000000000" ixz="-0.00000000000" + iyy="0.00003500000" iyz="0.00001700000" + izz="0.00002400000"/> + </inertial> + + <visual> + <origin xyz="0 0 0" rpy="0 0 0" /> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/inner_single.STL" scale="1 1 1"/> + </geometry> + <material name="Orange"/> + </visual> + + <collision> + <origin xyz="0 0 0" rpy="0 0 0" /> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/inner_single_collision.STL" scale="1 1 1"/> + </geometry> + </collision> + </link> + + <joint name="${name}_inner_single_joint" type="revolute"> + <parent link="${name}_base_link"/> + <child link="${name}_inner_single_link"/> + <origin xyz="0.00000 -0.00525 -0.05598" + rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/> + <axis xyz="1 0 0" /> + <limit lower="${0.0 * deg_to_rad}" upper="${60.0 * deg_to_rad}" effort="100.0" velocity="1.0" /> + <mimic joint="${name}_joint" multiplier="${-1.0}" offset="0.0" /> + + </joint> + + + <link name="${name}_fingertip_3_link"> + <inertial> + <origin xyz="0.00000 0.00460 -0.00254" rpy="0.00000 0.00000 0.00000"/> + <mass value="0.02630"/> + <inertia ixx="0.00000800000" ixy="0.00000000000" ixz="0.00000000000" + iyy="0.00000900000" iyz="0.00000100000" + izz="0.00000200000"/> + </inertial> + + <visual> + <origin xyz="0 0 0" rpy="0 0 0" /> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/fingertip.STL" scale="1 1 1"/> + </geometry> + <material name="DarkGrey"/> + </visual> + + <collision> + <origin xyz="0 0 0" rpy="0 0 0" /> + <geometry> + <mesh filename="package://talos_description/meshes/gripper/fingertip_collision.STL" scale="1 1 1"/> + </geometry> + </collision> + </link> + + <joint name="${name}_fingertip_3_joint" type="revolute"> + <parent link="${name}_inner_single_link"/> + <child link="${name}_fingertip_3_link"/> + <origin xyz="0.00000 -0.04589 -0.06553" + rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${180.00000 * deg_to_rad}"/> + <axis xyz="1 0 0" /> + <limit lower="${0.0 * deg_to_rad}" upper="${60.0 * deg_to_rad}" effort="100.0" velocity="1.0" /> + <mimic joint="${name}_joint" multiplier="${-1.0}" offset="0.0" /> + </joint> + + + + <xacro:virtual_joints name="${name}" /> + <xacro:gripper_transmission name="${name}" reduction="1.0" /> + + <!-- virtual mimic joints --> +<!-- <xacro:gripper_virtual_transmission name="${name}_inner_double" reduction="1.0"/> + <xacro:gripper_virtual_transmission name="${name}_fingertip_1" reduction="1.0"/> + <xacro:gripper_virtual_transmission name="${name}_fingertip_2" reduction="1.0"/> + <xacro:gripper_virtual_transmission name="${name}_inner_single" reduction="1.0"/> + <xacro:gripper_virtual_transmission name="${name}_motor_single" reduction="1.0"/> + <xacro:gripper_virtual_transmission name="${name}_fingertip_3" reduction="1.0"/> --> + </xacro:macro> </robot> diff --git a/talos_description/urdf/gripper/gripper_v2.urdf.xacro b/talos_description/urdf/gripper/gripper_v2.urdf.xacro deleted file mode 100644 index c1cd6c0ff2f96a1397cdfcee439c152791087bcb..0000000000000000000000000000000000000000 --- a/talos_description/urdf/gripper/gripper_v2.urdf.xacro +++ /dev/null @@ -1,320 +0,0 @@ -<?xml version="1.0"?> - -<robot xmlns:xacro="http://ros.org/wiki/xacro"> - - <!--File includes--> - <xacro:include filename="$(find talos_description)/urdf/deg_to_rad.xacro" /> - <xacro:include filename="$(find talos_description)/urdf/gripper/gripper.transmission.xacro" /> - <xacro:include filename="$(find talos_description)/urdf/gripper/gripper.gazebo.xacro" /> - - - <xacro:macro name="talos_gripper" params="name parent reflect"> - - <link name="${name}_base_link"> - <inertial> - <origin xyz="-0.00534 0.00362 -0.02357" rpy="0.00000 0.00000 0.00000"/> - <mass value="0.61585"/> - <inertia ixx="0.00047200000" ixy="-0.00000800000" ixz="0.00003500000" - iyy="0.00052100000" iyz="0.00000000000" - izz="0.00069000000"/> - </inertial> - - <visual> - <origin xyz="0 0 0" rpy="0 0 0" /> - <geometry> - <mesh filename="package://talos_description/meshes/gripper/base_link.STL" scale="1 1 1"/> - </geometry> - <material name="DarkGrey"/> - </visual> - - <collision> - <origin xyz="0 0 0" rpy="0 0 0" /> - <geometry> - <mesh filename="package://talos_description/meshes/gripper/base_link_collision.STL" scale="1 1 1"/> - </geometry> - </collision> - </link> - - <joint name="${name}_base_link_joint" type="fixed"> - <parent link="${parent}"/> - <child link="${name}_base_link"/> - <origin xyz="0.00000 0.00000 -0.02875" - rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/> - <axis xyz="0 0 0" /> - </joint> - - - <link name="${name}_motor_double_link"> - <inertial> - <origin xyz="0.02270 0.01781 -0.00977" rpy="0.00000 0.00000 0.00000"/> - <mass value="0.16889"/> - <!-- In order for Gazebo not to explode we needed to add these 0.001 values to the diagonal, - also the tool pal_dynamics InertiaMassVisualization gave NaN on the computation of the inertia box --> - <inertia ixx="${0.00015900000 + 0.001}" ixy="-0.00007000000" ixz="0.00003800000" - iyy="${0.00022100000 + 0.001}" iyz="-0.00005300000" - izz="${0.00026800000 + 0.001}"/> - </inertial> - - <visual> - <origin xyz="0 0 0" rpy="0 0 0" /> - <geometry> - <mesh filename="package://talos_description/meshes/gripper/gripper_motor_double.STL" scale="1 1 1"/> - </geometry> - <material name="Orange"/> - </visual> - - <collision> - <origin xyz="0 0 0" rpy="0 0 0" /> - <geometry> - <mesh filename="package://talos_description/meshes/gripper/gripper_motor_double_collision.STL" scale="1 1 1"/> - </geometry> - </collision> - </link> - - <joint name="${name}_joint" type="revolute"> - <parent link="${name}_base_link"/> - <child link="${name}_motor_double_link"/> - <origin xyz="0.0 0.02025 -0.03" - rpy="${0.0 * deg_to_rad} ${0.0 * deg_to_rad} ${0.0 * deg_to_rad}"/> - <axis xyz="1 0 0" /> - <limit lower="${-60.0 * deg_to_rad}" upper="${0.0 * deg_to_rad}" effort="1.0" velocity="1.0" /> - <dynamics friction="1.0" damping="1.0"/> - </joint> - - - <link name="${name}_inner_double_link"> - <inertial> - <origin xyz="-0.00056 0.03358 -0.01741" rpy="0.00000 0.00000 0.00000"/> - <mass value="0.11922"/> - <inertia ixx="0.00009100000" ixy="0.00000100000" ixz="-0.00000100000" - iyy="0.00015600000" iyz="-0.00003200000" - izz="0.00012600000"/> - </inertial> - - <visual> - <origin xyz="0 0 0" rpy="0 0 0" /> - <geometry> - <mesh filename="package://talos_description/meshes/gripper/inner_double.STL" scale="1 1 1"/> - </geometry> - <material name="Orange"/> - </visual> - - <collision> - <origin xyz="0 0 0" rpy="0 0 0" /> - <geometry> - <mesh filename="package://talos_description/meshes/gripper/inner_double_collision.STL" scale="1 1 1"/> - </geometry> - </collision> - </link> - - <joint name="${name}_inner_double_joint" type="revolute"> - <parent link="${name}_base_link"/> - <child link="${name}_inner_double_link"/> - <origin xyz="0.00000 0.00525 -0.05598" - rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/> - <axis xyz="1 0 0" /> - <limit lower="${-60.0 * deg_to_rad}" upper="${0.0 * deg_to_rad}" effort="100.0" velocity="1.0" /> - <mimic joint="${name}_joint" multiplier="${1.0}" offset="0.0" /> - - </joint> - - - - <link name="${name}_fingertip_1_link"> - <inertial> - <origin xyz="0.00000 0.00460 -0.00254" rpy="0.00000 0.00000 0.00000"/> - <mass value="0.02630"/> - <inertia ixx="0.00000800000" ixy="0.00000000000" ixz="0.00000000000" - iyy="0.00000900000" iyz="0.00000100000" - izz="0.00000200000"/> - </inertial> - - <visual> - <origin xyz="0 0 0" rpy="0 0 0" /> - <geometry> - <mesh filename="package://talos_description/meshes/gripper/fingertip.STL" scale="1 1 1"/> - </geometry> - <material name="DarkGrey"/> - </visual> - - <collision> - <origin xyz="0 0 0" rpy="0 0 0" /> - <geometry> - <mesh filename="package://talos_description/meshes/gripper/fingertip_collision.STL" scale="1 1 1"/> - </geometry> - </collision> - </link> - - - <joint name="${name}_fingertip_1_joint" type="revolute"> - <parent link="${name}_inner_double_link"/> - <child link="${name}_fingertip_1_link"/> - <origin xyz="0.03200 0.04589 -0.06553" - rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/> - <axis xyz="1 0 0" /> - <limit lower="${0.0 * deg_to_rad}" upper="${60.0 * deg_to_rad}" effort="100.0" velocity="1.0" /> - <mimic joint="${name}_joint" multiplier="${-1.0}" offset="0.0" /> - </joint> - - - <link name="${name}_fingertip_2_link"> - <inertial> - <origin xyz="0.00000 0.00460 -0.00254" rpy="0.00000 0.00000 0.00000"/> - <mass value="0.02630"/> - <inertia ixx="0.00000800000" ixy="0.00000000000" ixz="0.00000000000" - iyy="0.00000900000" iyz="0.00000100000" - izz="0.00000200000"/> - </inertial> - - <visual> - <origin xyz="0 0 0" rpy="0 0 0" /> - <geometry> - <mesh filename="package://talos_description/meshes/gripper/fingertip.STL" scale="1 1 1"/> - </geometry> - <material name="DarkGrey"/> - </visual> - - <collision> - <origin xyz="0 0 0" rpy="0 0 0" /> - <geometry> - <mesh filename="package://talos_description/meshes/gripper/fingertip_collision.STL" scale="1 1 1"/> - </geometry> - </collision> - </link> - - <joint name="${name}_fingertip_2_joint" type="revolute"> - <parent link="${name}_inner_double_link"/> - <child link="${name}_fingertip_2_link"/> - <origin xyz="-0.03200 0.04589 -0.06553" - rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/> - <axis xyz="1 0 0" /> - <limit lower="${0.0 * deg_to_rad}" upper="${60.0 * deg_to_rad}" effort="100.0" velocity="1.0" /> - <mimic joint="${name}_joint" multiplier="${-1.0}" offset="0.0" /> - </joint> - - - <link name="${name}_motor_single_link"> - <inertial> - <origin xyz="0.02589 -0.01284 -0.00640" rpy="0.00000 0.00000 0.00000"/> - <mass value="0.14765"/> - <inertia ixx="0.00011500000" ixy="0.00005200000" ixz="0.00002500000" - iyy="0.00015300000" iyz="0.00003400000" - izz="0.00019000000"/> - </inertial> - - <visual> - <origin xyz="0 0 0" rpy="0 0 0" /> - <geometry> - <mesh filename="package://talos_description/meshes/gripper/gripper_motor_single.STL" scale="1 1 1"/> - </geometry> - <material name="Orange"/> - </visual> - - <collision> - <origin xyz="0 0 0" rpy="0 0 0" /> - <geometry> - <mesh filename="package://talos_description/meshes/gripper/gripper_motor_single_collision.STL" scale="1 1 1"/> - </geometry> - </collision> - </link> - - <joint name="${name}_motor_single_joint" type="revolute"> - <parent link="${name}_base_link"/> - <child link="${name}_motor_single_link"/> - <origin xyz="0.00000 -0.02025 -0.03000" - rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/> - <axis xyz="1 0 0" /> - <limit lower="${0.0 * deg_to_rad}" upper="${60.0 * deg_to_rad}" effort="100.0" velocity="1.0" /> - <mimic joint="${name}_joint" multiplier="${-1.0}" offset="0.0" /> - </joint> - - - - <link name="${name}_inner_single_link"> - <inertial> - <origin xyz="0.00000 -0.03253 -0.01883" rpy="0.00000 0.00000 0.00000"/> - <mass value="0.05356"/> - <inertia ixx="0.00004700000" ixy="-0.00000000000" ixz="-0.00000000000" - iyy="0.00003500000" iyz="0.00001700000" - izz="0.00002400000"/> - </inertial> - - <visual> - <origin xyz="0 0 0" rpy="0 0 0" /> - <geometry> - <mesh filename="package://talos_description/meshes/gripper/inner_single.STL" scale="1 1 1"/> - </geometry> - <material name="Orange"/> - </visual> - - <collision> - <origin xyz="0 0 0" rpy="0 0 0" /> - <geometry> - <mesh filename="package://talos_description/meshes/gripper/inner_single_collision.STL" scale="1 1 1"/> - </geometry> - </collision> - </link> - - <joint name="${name}_inner_single_joint" type="revolute"> - <parent link="${name}_base_link"/> - <child link="${name}_inner_single_link"/> - <origin xyz="0.00000 -0.00525 -0.05598" - rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/> - <axis xyz="1 0 0" /> - <limit lower="${0.0 * deg_to_rad}" upper="${60.0 * deg_to_rad}" effort="100.0" velocity="1.0" /> - <mimic joint="${name}_joint" multiplier="${-1.0}" offset="0.0" /> - - </joint> - - - <link name="${name}_fingertip_3_link"> - <inertial> - <origin xyz="0.00000 0.00460 -0.00254" rpy="0.00000 0.00000 0.00000"/> - <mass value="0.02630"/> - <inertia ixx="0.00000800000" ixy="0.00000000000" ixz="0.00000000000" - iyy="0.00000900000" iyz="0.00000100000" - izz="0.00000200000"/> - </inertial> - - <visual> - <origin xyz="0 0 0" rpy="0 0 0" /> - <geometry> - <mesh filename="package://talos_description/meshes/gripper/fingertip.STL" scale="1 1 1"/> - </geometry> - <material name="DarkGrey"/> - </visual> - - <collision> - <origin xyz="0 0 0" rpy="0 0 0" /> - <geometry> - <mesh filename="package://talos_description/meshes/gripper/fingertip_collision.STL" scale="1 1 1"/> - </geometry> - </collision> - </link> - - <joint name="${name}_fingertip_3_joint" type="revolute"> - <parent link="${name}_inner_single_link"/> - <child link="${name}_fingertip_3_link"/> - <origin xyz="0.00000 -0.04589 -0.06553" - rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${180.00000 * deg_to_rad}"/> - <axis xyz="1 0 0" /> - <limit lower="${0.0 * deg_to_rad}" upper="${60.0 * deg_to_rad}" effort="100.0" velocity="1.0" /> - <mimic joint="${name}_joint" multiplier="${-1.0}" offset="0.0" /> - </joint> - - - - <xacro:virtual_joints name="${name}" /> - <xacro:gripper_transmission name="${name}" reduction="1.0" /> - - <!-- virtual mimic joints --> -<!-- <xacro:gripper_virtual_transmission name="${name}_inner_double" reduction="1.0"/> - <xacro:gripper_virtual_transmission name="${name}_fingertip_1" reduction="1.0"/> - <xacro:gripper_virtual_transmission name="${name}_fingertip_2" reduction="1.0"/> - <xacro:gripper_virtual_transmission name="${name}_inner_single" reduction="1.0"/> - <xacro:gripper_virtual_transmission name="${name}_motor_single" reduction="1.0"/> - <xacro:gripper_virtual_transmission name="${name}_fingertip_3" reduction="1.0"/> --> - - </xacro:macro> - -</robot> diff --git a/talos_description/urdf/leg/leg.urdf.xacro b/talos_description/urdf/leg/leg.urdf.xacro index 71ded42aea29d3588582bca4746295b62091e2ff..5bedc07f07e7097d3e808c0710c9e59199712889 100644 --- a/talos_description/urdf/leg/leg.urdf.xacro +++ b/talos_description/urdf/leg/leg.urdf.xacro @@ -1,157 +1,255 @@ <?xml version="1.0"?> -<robot name="talos" xmlns:xacro="http://ros.org/wiki/xacro" > - <xacro:include filename="$(find talos_description)/urdf/leg/leg.transmission.xacro" /> - <xacro:property name="leg_reduction" value="1.0" /> - <xacro:property name="leg_friction" value="0.0" /> - <xacro:property name="leg_damping" value="0.0" /> +<robot xmlns:xacro="http://ros.org/wiki/xacro" name="talos"> + + <xacro:include filename="$(find talos_description)/urdf/leg/leg.transmission.xacro" /> + + <xacro:property name="deg_to_rad" value="0.01745329251994329577" /> + <xacro:property name="eps_radians" value="0.008" /> <!-- 0.45deg --> + <xacro:property name="eps_meters" value="0.005" /> + <xacro:property name="leg_reduction" value="1.0" /> + <xacro:property name="leg_friction" value="0.0" /> + <xacro:property name="leg_damping" value="0.0" /> + + + <xacro:macro name="talos_leg" params="prefix reflect"> + <!-- Joint hip_z (mesh link) : child link hip_x -> parent link base_link --> - <xacro:macro name="talos_leg" params="prefix reflect"> - <link name="leg_${prefix}_1_link"> <inertial> - <origin xyz="0.033 0.0 -0.112" rpy="0 0 0"/> - <mass value="1.3" /> - <inertia ixx="0.003" ixy="0.0" ixz="0.0" iyy="0.004" iyz="0.0" izz="0.002" /> + <origin xyz="0.02320 -0.00009 0.04949" rpy="0.00000 0.00000 0.00000"/> + <mass value="1.88569"/> + <inertia ixx="0.00384800000" ixy="0.00003200000" ixz="-0.00082600000" + iyy="0.00599400000" iyz="0.00007800000" + izz="0.00322200000"/> </inertial> - + <visual> - <origin rpy="0 0 3.14" xyz="0 0 0"/> + <origin rpy="0 0 0" xyz="0 0 0"/> <geometry> - <mesh filename="package://talos_description/meshes/hipZ.STL" scale="1 ${reflect*1} 1"/> + <mesh filename="package://talos_description/meshes/v2/hip_z_lo_res.stl" scale="1 ${reflect*1} 1"/> </geometry> - <!-- <material name="LightGrey" /> --> + <material name="DarkGrey" /> </visual> - + <collision> - <origin rpy="0 0 0" xyz="0 0 -0.02"/> - <geometry> - <box size="0.1 0.1 0.1"/> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="package://talos_description/meshes/v2/hip_z_collision.stl" scale="1 ${reflect*1} 1"/> </geometry> </collision> - </link> + <joint name="leg_${prefix}_1_joint" type="revolute"> + <parent link="base_link"/> + <child link="leg_${prefix}_1_link"/> + <origin xyz="-0.02 ${reflect*0.08500} -0.27105" + rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/> + <axis xyz="0 0 1" /> + <limit lower="${(-55.0 + 35.0*reflect)*deg_to_rad}" upper="${(55.0 + 35.0*reflect)*deg_to_rad}" effort="100" velocity="3.87" /> + <dynamics friction="${leg_friction}" damping="${leg_damping}"/> + </joint> + + + <!-- Joint hip_x (mesh link) : child link hip_y -> parent link hip_z --> + <link name="leg_${prefix}_2_link"> <inertial> - <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/> - <mass value="1.2" /> - <inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001" /> + <origin xyz="0.01583 -0.00021 0.00619" rpy="0.00000 0.00000 0.00000"/> + <mass value="2.37607"/> + <inertia ixx="0.00342100000" ixy="-0.00011300000" ixz="-0.00022500000" + iyy="0.00402400000" iyz="-0.00003100000" + izz="0.00416400000"/> </inertial> <visual> - <origin xyz="0 0 0.0" rpy="1.57 0 0" /> + <origin xyz="0 0 0.0" rpy="0 0 0" /> <geometry> - <cylinder radius="0.05" length="0.15"/> + <mesh filename="package://talos_description/meshes/v2/hip_x_lo_res.stl" scale="1 ${reflect*1} 1"/> </geometry> <material name="DarkGrey" /> </visual> <collision> - <origin xyz="0 0 0.0" rpy="1.57 0 0" /> + <origin xyz="0 0 0.0" rpy="0 0 0" /> <geometry> - <cylinder radius="0.05" length="0.15"/> + <mesh filename="package://talos_description/meshes/v2/hip_x_collision.stl" scale="1 ${reflect*1} 1"/> </geometry> - </collision> + </collision> + </link> + + <joint name="leg_${prefix}_2_joint" type="revolute"> + <parent link="leg_${prefix}_1_link"/> + <child link="leg_${prefix}_2_link"/> + <origin xyz="0.00000 0.00000 0.00000" + rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/> + <axis xyz="1 0 0" /> + <limit lower="-0.5236" upper="0.5236" effort="160" velocity="5.8" /> + <dynamics friction="${leg_friction}" damping="${leg_damping}"/> + </joint> + + <!-- Joint hip_y (mesh link) : child link knee -> parent link hip_x --> - </link> - <link name="leg_${prefix}_3_link"> + <inertial> + <origin xyz="0.00658 ${reflect*0.06563} -0.17278" rpy="0.00000 0.00000 0.00000"/> + <mass value="6.82734"/> + <inertia ixx="0.12390600000" ixy="${reflect*-0.00041200000}" ixz="-0.00205900000" + iyy="0.10844700000" iyz="${reflect*0.01672500000}" + izz="0.02781200000"/> + </inertial> + <visual> <origin rpy="0 0 0" xyz="0 0 0"/> <geometry> - <mesh filename="package://talos_description/meshes/femur.STL" scale="1 ${reflect*1} 1"/> + <mesh filename="package://talos_description/meshes/v2/hip_y_lo_res.stl" scale="1 ${reflect*1} 1"/> </geometry> - <!-- <material name="LightGrey" /> --> + <material name="DarkGrey" /> </visual> <collision> - <origin rpy="0 0 0" xyz="0 0 -0.2"/> + <origin rpy="0 0 0" xyz="0 0 0"/> <geometry> - <box size="0.1 0.15 0.25"/> + <mesh filename="package://talos_description/meshes/v2/hip_y_collision.stl" scale="1 ${reflect*1} 1"/> </geometry> </collision> + </link> - <inertial> - <origin xyz="0.005 ${reflect*0.057} -0.195" rpy="0 0 0"/> - <mass value="6.4" /> - <inertia ixx="0.117" ixy="${reflect*-0.001}" ixz="0.001" iyy="0.106" iyz="${reflect*0.018}" izz="0.021" /> - </inertial> - </link> + <joint name="leg_${prefix}_3_joint" type="revolute"> + <parent link="leg_${prefix}_2_link"/> + <child link="leg_${prefix}_3_link"/> + <origin xyz="0.00000 0.00000 0.00000" + rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/> + <axis xyz="0 1 0" /> + <limit lower="-2.095" upper="0.7" effort="160" velocity="5.8" /> + <dynamics friction="${leg_friction}" damping="${leg_damping}"/> + </joint> + + <!-- Joint knee (mesh link) : child link ankle_y -> parent link hip_y --> <link name="leg_${prefix}_4_link"> - <inertial> - <origin xyz="0.008 ${reflect*0.033} -0.139" rpy="0 0 0"/> - <mass value="3.6" /> - <inertia ixx="0.033" ixy="${reflect*-0.001}" ixz="0.001" iyy="0.028" iyz="0.0" izz="0.011" /> + <origin xyz="0.01520 ${reflect*0.02331} -0.12063" rpy="0.00000 0.00000 0.00000"/> + <mass value="3.63668"/> + <inertia ixx="0.03531500000" ixy="${reflect*0.00002900000}" ixz="-0.00016600000" + iyy="0.02933600000" iyz="${reflect*-0.00130500000}" + izz="0.01174000000"/> </inertial> - - <visual> + + <visual> <origin rpy="0 0 0" xyz="0 0 0"/> <geometry> - <mesh filename="package://talos_description/meshes/tibia.STL" scale="1 ${reflect*1} 1"/> + <mesh filename="package://talos_description/meshes/v2/knee_lo_res.stl" scale="1 ${reflect*1} 1"/> </geometry> - <!-- <material name="LightGrey" /> --> + <material name="DarkGrey" /> </visual> <collision> - <origin rpy="0 0 0" xyz="0 0 -0.175"/> + <origin rpy="0 0 0" xyz="0 0 0"/> <geometry> - <box size="0.1 0.15 0.3"/> + <mesh filename="package://talos_description/meshes/v2/knee_collision.stl" scale="1 ${reflect*1} 1"/> </geometry> </collision> + </link> + + <joint name="leg_${prefix}_4_joint" type="revolute"> + <parent link="leg_${prefix}_3_link"/> + <child link="leg_${prefix}_4_link"/> - </link> + <origin xyz="0.00000 0.00000 -0.38000" + rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/> + <axis xyz="0 1 0" /> + <limit lower="0" upper="2.618" effort="300" velocity="7" /> + <dynamics friction="${leg_friction}" damping="${leg_damping}"/> + </joint> + + <!-- Joint ankle_y (mesh link) : child link ankle_x -> parent link knee --> <link name="leg_${prefix}_5_link"> - <inertial> - <origin xyz="-0.003 ${reflect*0.007} -0.005" rpy="0 0 0"/> - <mass value="1.1" /> - <inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001" /> + <origin xyz="-0.01106 ${reflect*0.04708} 0.05271" rpy="0.00000 0.00000 0.00000"/> + <mass value="1.24433"/> + <inertia ixx="0.01148700000" ixy="${reflect*-0.00068600000}" ixz="-0.00052600000" + iyy="0.00952600000" iyz="${reflect*0.00263300000}" + izz="0.00390800000"/> </inertial> - + <visual> - <origin xyz="0 0 0.0" rpy="1.57 0 0" /> - <geometry> - <cylinder radius="0.01" length="0.14"/> + <origin xyz="0 0 0.0" rpy="0 0 0" /> + <geometry> + <mesh filename="package://talos_description/meshes/v2/ankle_Y_lo_res.stl" scale="1 ${reflect*1} 1"/> </geometry> <material name="Grey" /> </visual> <collision> - <origin xyz="0 0 0.0" rpy="1.57 0 0" /> - <geometry> - <cylinder radius="0.01" length="0.14"/> + <origin xyz="0 0 0.0" rpy="0 0 0" /> + <geometry> + <mesh filename="package://talos_description/meshes/v2/ankle_Y_collision.stl" scale="1 ${reflect*1} 1"/> </geometry> </collision> - - </link> - - <link name="leg_${prefix}_6_link"> + </link> + + <joint name="leg_${prefix}_5_joint" type="revolute"> + <parent link="leg_${prefix}_4_link"/> + <child link="leg_${prefix}_5_link"/> + <origin xyz="0.00000 0.00000 -0.32500" + rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/> + <axis xyz="0 1 0" /> + <limit lower="-1.309" upper="0.768" effort="160" velocity="5.8" /> + <dynamics friction="${leg_friction}" damping="${leg_damping}"/> + </joint> + + <!-- Joint ankle_x (mesh link) : child link None -> parent link ankle_y --> + + <link name="leg_${prefix}_6_link"> <inertial> - <origin xyz="-0.008 0.0 -0.097" rpy="0 0 0"/> - <mass value="0.9" /> - <inertia ixx="0.002" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001" /> + <origin xyz="-0.02087 -0.00019 -0.06059" rpy="0.00000 0.00000 0.00000"/> + <mass value="1.59457"/> + <inertia ixx="0.00383800000" ixy="0.00001600000" ixz="-0.00104100000" + iyy="0.00657200000" iyz="-0.00001700000" + izz="0.00504400000"/> </inertial> + <visual> <origin rpy="0 0 0" xyz="0 0 0"/> <geometry> - <mesh filename="package://talos_description/meshes/foot.STL" scale="1 ${reflect*1} 1"/> + <mesh filename="package://talos_description/meshes/v2/ankle_X_lo_res.stl" scale="1 ${reflect*1} 1"/> </geometry> - <!-- <material name="LightGrey" /> --> + <material name="Grey" /> </visual> + + <!-- <collision> + <origin xyz="0 0 0" rpy="0 0 0" /> + <geometry> + <mesh filename="package://talos_description/meshes/v2/ankle_X_collision.stl" scale="1 ${reflect*1} 1"/> + </geometry> + </collision> + + --> + + <collision> <origin xyz="0 0 -0.1" rpy="0 0 0" /> <geometry> <box size="0.21 0.13 0.02"/> </geometry> </collision> + + </link> + + <joint name="leg_${prefix}_6_joint" type="revolute"> + <parent link="leg_${prefix}_5_link"/> + <child link="leg_${prefix}_6_link"/> + <origin xyz="0.00000 0.00000 0.00000" + rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/> + <axis xyz="1 0 0" /> + <limit lower="-0.5236" upper="0.5236" effort="100" velocity="4.8" /> + <dynamics friction="${leg_friction}" damping="${leg_damping}"/> + </joint> + + <!-- from here is copy paste --> - </link> - - <link name="${prefix}_sole_link"> <inertial> <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/> @@ -160,85 +258,6 @@ </inertial> </link> - <joint name="leg_${prefix}_1_joint" type="revolute"> - <parent link="base_link" /> - <child link="leg_${prefix}_1_link" /> - <origin xyz="0.0 ${reflect*0.08} 0.0" rpy="0 0 0" /> - <axis xyz="0 0 1" /> - <!-- nominal --> - <!-- <limit lower="-0.5236" upper="1.571" effort="49" velocity="3.87" /> --> - <!-- peak --> - <xacro:if value="${reflect == 1}"> - <limit lower="-0.5236" upper="1.571" effort="100" velocity="3.87" /> - </xacro:if> - <xacro:if value="${reflect == -1}"> - <limit lower="-1.571" upper="0.5236" effort="100" velocity="3.87" /> - </xacro:if> - <dynamics friction="${leg_friction}" damping="${leg_damping}"/> - </joint> - - <joint name="leg_${prefix}_2_joint" type="revolute"> - <parent link="leg_${prefix}_1_link" /> - <child link="leg_${prefix}_2_link" /> - <origin xyz="0.0 0.0 -0.10" rpy="0 0 0" /> - <axis xyz="1 0 0" /> - <!-- nominal --> - <!-- <limit lower="-0.524" upper="0.5236" effort="90" velocity="5.8" /> --> - <!--peak --> - <limit lower="-0.524" upper="0.5236" effort="160" velocity="5.8" /> - <dynamics friction="${leg_friction}" damping="${leg_damping}"/> - </joint> - - <joint name="leg_${prefix}_3_joint" type="revolute"> - <parent link="leg_${prefix}_2_link" /> - <child link="leg_${prefix}_3_link" /> - <origin xyz="0.0 0.0 -0.0" rpy="0 0 0" /> - <axis xyz="0 1 0" /> - <!-- nomial --> - <!-- <limit lower="-2.095" upper="0.7" effort="90" velocity="5.8" /> --> - <!-- peak --> - <limit lower="-2.095" upper="0.7" effort="160" velocity="5.8" /> - <dynamics friction="${leg_friction}" damping="${leg_damping}"/> - </joint> - - - <joint name="leg_${prefix}_4_joint" type="revolute"> - <parent link="leg_${prefix}_3_link" /> - <child link="leg_${prefix}_4_link" /> - <origin xyz="0.00 -0.0 -0.38" rpy="0 0 0" /> - <axis xyz="0 1 0" /> - <!-- nominal --> - <!-- <limit lower="0" upper="2.618" effort="145" velocity="7" /> --> - <!-- peak --> - <limit lower="0" upper="2.618" effort="300" velocity="7" /> - <dynamics friction="${leg_friction}" damping="${leg_damping}"/> - </joint> - - - <joint name="leg_${prefix}_5_joint" type="revolute"> - <parent link="leg_${prefix}_4_link" /> - <child link="leg_${prefix}_5_link" /> - <origin xyz="0.00 0.00 -0.32" rpy="0 0 0" /> - <axis xyz="0 1 0" /> - <!-- nominal --> - <!-- <limit lower="-1.309" upper="0.768" effort="90" velocity="5.8" /> --> - <!-- peak --> - <limit lower="-1.309" upper="0.768" effort="160" velocity="5.8" /> - <dynamics friction="${leg_friction}" damping="${leg_damping}"/> - </joint> - - <joint name="leg_${prefix}_6_joint" type="revolute"> - <parent link="leg_${prefix}_5_link" /> - <child link="leg_${prefix}_6_link" /> - <origin xyz="0.00 0.00 -0.0" rpy="0 0 0" /> - <axis xyz="1 0 0" /> - <!-- nominal --> - <!-- <limit lower="-0.524" upper="0.524" effort="62" velocity="4.8" /> --> - <!-- peak --> - <limit lower="-0.524" upper="0.524" effort="100" velocity="4.8" /> - </joint> - - <joint name="leg_${prefix}_sole_fix_joint" type="fixed"> <parent link="leg_${prefix}_6_link" /> <child link="${prefix}_sole_link" /> @@ -275,52 +294,57 @@ <mu2>0.9</mu2> </gazebo> - <!-- - - <gazebo reference="leg_${prefix}_6_link"> - <kp>1000000.0</kp> - <kd>100.0</kd> - <mu1>1.0</mu1> - <mu2>1.0</mu2> - <fdir1>0 0 1</fdir1> - <maxVel>1.0</maxVel> - <minDepth>0.003</minDepth> - <implicitSpringDamper>1</implicitSpringDamper> - </gazebo> - - --> - + <!-- contact model for foot surface --> <gazebo reference="leg_${prefix}_6_link"> <kp>1000000.0</kp> <kd>100.0</kd> - <mu1>1.5</mu1> - <mu2>1.5</mu2> + <mu1>1.0</mu1> + <mu2>1.0</mu2> <fdir1>1 0 0</fdir1> <maxVel>1.0</maxVel> <minDepth>0.00</minDepth> + <implicitSpringDamper>1</implicitSpringDamper> </gazebo> <gazebo reference="leg_${prefix}_1_joint"> - <implicitSpringDamper>0.1</implicitSpringDamper> + <implicitSpringDamper>1</implicitSpringDamper> </gazebo> <gazebo reference="leg_${prefix}_2_joint"> - <implicitSpringDamper>0.1</implicitSpringDamper> + <implicitSpringDamper>1</implicitSpringDamper> </gazebo> <gazebo reference="leg_${prefix}_3_joint"> - <implicitSpringDamper>0.1</implicitSpringDamper> + <implicitSpringDamper>1</implicitSpringDamper> </gazebo> <gazebo reference="leg_${prefix}_4_joint"> - <implicitSpringDamper>0.1</implicitSpringDamper> + <implicitSpringDamper>1</implicitSpringDamper> </gazebo> <gazebo reference="leg_${prefix}_5_joint"> - <implicitSpringDamper>0.1</implicitSpringDamper> + <implicitSpringDamper>1</implicitSpringDamper> </gazebo> <gazebo reference="leg_${prefix}_6_joint"> - <implicitSpringDamper>0.1</implicitSpringDamper> + <implicitSpringDamper>1</implicitSpringDamper> <provideFeedback>1</provideFeedback> </gazebo> - + + <gazebo reference="leg_${prefix}_1_link"> + <material>Gazebo/FlatBlack</material> + </gazebo> + <gazebo reference="leg_${prefix}_2_link"> + <material>Gazebo/FlatBlack</material> + </gazebo> + <gazebo reference="leg_${prefix}_3_link"> + <material>Gazebo/FlatBlack</material> + </gazebo> + <gazebo reference="leg_${prefix}_4_link"> + <material>Gazebo/FlatBlack</material> + </gazebo> + <gazebo reference="leg_${prefix}_5_link"> + <material>Gazebo/White</material> + </gazebo> + <gazebo reference="leg_${prefix}_6_link"> + <material>Gazebo/White</material> + </gazebo> + </xacro:macro> - </robot> diff --git a/talos_description/urdf/leg/leg_v2.urdf.xacro b/talos_description/urdf/leg/leg_v2.urdf.xacro deleted file mode 100644 index 5bedc07f07e7097d3e808c0710c9e59199712889..0000000000000000000000000000000000000000 --- a/talos_description/urdf/leg/leg_v2.urdf.xacro +++ /dev/null @@ -1,350 +0,0 @@ -<?xml version="1.0"?> - -<robot xmlns:xacro="http://ros.org/wiki/xacro" name="talos"> - - <xacro:include filename="$(find talos_description)/urdf/leg/leg.transmission.xacro" /> - - <xacro:property name="deg_to_rad" value="0.01745329251994329577" /> - <xacro:property name="eps_radians" value="0.008" /> <!-- 0.45deg --> - <xacro:property name="eps_meters" value="0.005" /> - <xacro:property name="leg_reduction" value="1.0" /> - <xacro:property name="leg_friction" value="0.0" /> - <xacro:property name="leg_damping" value="0.0" /> - - - <xacro:macro name="talos_leg" params="prefix reflect"> - <!-- Joint hip_z (mesh link) : child link hip_x -> parent link base_link --> - - <link name="leg_${prefix}_1_link"> - <inertial> - <origin xyz="0.02320 -0.00009 0.04949" rpy="0.00000 0.00000 0.00000"/> - <mass value="1.88569"/> - <inertia ixx="0.00384800000" ixy="0.00003200000" ixz="-0.00082600000" - iyy="0.00599400000" iyz="0.00007800000" - izz="0.00322200000"/> - </inertial> - - <visual> - <origin rpy="0 0 0" xyz="0 0 0"/> - <geometry> - <mesh filename="package://talos_description/meshes/v2/hip_z_lo_res.stl" scale="1 ${reflect*1} 1"/> - </geometry> - <material name="DarkGrey" /> - </visual> - - <collision> - <origin rpy="0 0 0" xyz="0 0 0"/> - <geometry> - <mesh filename="package://talos_description/meshes/v2/hip_z_collision.stl" scale="1 ${reflect*1} 1"/> - </geometry> - </collision> - </link> - - <joint name="leg_${prefix}_1_joint" type="revolute"> - <parent link="base_link"/> - <child link="leg_${prefix}_1_link"/> - <origin xyz="-0.02 ${reflect*0.08500} -0.27105" - rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/> - <axis xyz="0 0 1" /> - <limit lower="${(-55.0 + 35.0*reflect)*deg_to_rad}" upper="${(55.0 + 35.0*reflect)*deg_to_rad}" effort="100" velocity="3.87" /> - <dynamics friction="${leg_friction}" damping="${leg_damping}"/> - </joint> - - - <!-- Joint hip_x (mesh link) : child link hip_y -> parent link hip_z --> - - <link name="leg_${prefix}_2_link"> - <inertial> - <origin xyz="0.01583 -0.00021 0.00619" rpy="0.00000 0.00000 0.00000"/> - <mass value="2.37607"/> - <inertia ixx="0.00342100000" ixy="-0.00011300000" ixz="-0.00022500000" - iyy="0.00402400000" iyz="-0.00003100000" - izz="0.00416400000"/> - </inertial> - - <visual> - <origin xyz="0 0 0.0" rpy="0 0 0" /> - <geometry> - <mesh filename="package://talos_description/meshes/v2/hip_x_lo_res.stl" scale="1 ${reflect*1} 1"/> - </geometry> - <material name="DarkGrey" /> - </visual> - - <collision> - <origin xyz="0 0 0.0" rpy="0 0 0" /> - <geometry> - <mesh filename="package://talos_description/meshes/v2/hip_x_collision.stl" scale="1 ${reflect*1} 1"/> - </geometry> - </collision> - </link> - - <joint name="leg_${prefix}_2_joint" type="revolute"> - <parent link="leg_${prefix}_1_link"/> - <child link="leg_${prefix}_2_link"/> - <origin xyz="0.00000 0.00000 0.00000" - rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/> - <axis xyz="1 0 0" /> - <limit lower="-0.5236" upper="0.5236" effort="160" velocity="5.8" /> - <dynamics friction="${leg_friction}" damping="${leg_damping}"/> - </joint> - - <!-- Joint hip_y (mesh link) : child link knee -> parent link hip_x --> - - <link name="leg_${prefix}_3_link"> - <inertial> - <origin xyz="0.00658 ${reflect*0.06563} -0.17278" rpy="0.00000 0.00000 0.00000"/> - <mass value="6.82734"/> - <inertia ixx="0.12390600000" ixy="${reflect*-0.00041200000}" ixz="-0.00205900000" - iyy="0.10844700000" iyz="${reflect*0.01672500000}" - izz="0.02781200000"/> - </inertial> - - <visual> - <origin rpy="0 0 0" xyz="0 0 0"/> - <geometry> - <mesh filename="package://talos_description/meshes/v2/hip_y_lo_res.stl" scale="1 ${reflect*1} 1"/> - </geometry> - <material name="DarkGrey" /> - </visual> - - <collision> - <origin rpy="0 0 0" xyz="0 0 0"/> - <geometry> - <mesh filename="package://talos_description/meshes/v2/hip_y_collision.stl" scale="1 ${reflect*1} 1"/> - </geometry> - </collision> - </link> - - <joint name="leg_${prefix}_3_joint" type="revolute"> - <parent link="leg_${prefix}_2_link"/> - <child link="leg_${prefix}_3_link"/> - <origin xyz="0.00000 0.00000 0.00000" - rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/> - <axis xyz="0 1 0" /> - <limit lower="-2.095" upper="0.7" effort="160" velocity="5.8" /> - <dynamics friction="${leg_friction}" damping="${leg_damping}"/> - </joint> - - <!-- Joint knee (mesh link) : child link ankle_y -> parent link hip_y --> - - <link name="leg_${prefix}_4_link"> - <inertial> - <origin xyz="0.01520 ${reflect*0.02331} -0.12063" rpy="0.00000 0.00000 0.00000"/> - <mass value="3.63668"/> - <inertia ixx="0.03531500000" ixy="${reflect*0.00002900000}" ixz="-0.00016600000" - iyy="0.02933600000" iyz="${reflect*-0.00130500000}" - izz="0.01174000000"/> - </inertial> - - <visual> - <origin rpy="0 0 0" xyz="0 0 0"/> - <geometry> - <mesh filename="package://talos_description/meshes/v2/knee_lo_res.stl" scale="1 ${reflect*1} 1"/> - </geometry> - <material name="DarkGrey" /> - </visual> - - <collision> - <origin rpy="0 0 0" xyz="0 0 0"/> - <geometry> - <mesh filename="package://talos_description/meshes/v2/knee_collision.stl" scale="1 ${reflect*1} 1"/> - </geometry> - </collision> - </link> - - <joint name="leg_${prefix}_4_joint" type="revolute"> - <parent link="leg_${prefix}_3_link"/> - <child link="leg_${prefix}_4_link"/> - - <origin xyz="0.00000 0.00000 -0.38000" - rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/> - <axis xyz="0 1 0" /> - <limit lower="0" upper="2.618" effort="300" velocity="7" /> - <dynamics friction="${leg_friction}" damping="${leg_damping}"/> - </joint> - - <!-- Joint ankle_y (mesh link) : child link ankle_x -> parent link knee --> - - <link name="leg_${prefix}_5_link"> - <inertial> - <origin xyz="-0.01106 ${reflect*0.04708} 0.05271" rpy="0.00000 0.00000 0.00000"/> - <mass value="1.24433"/> - <inertia ixx="0.01148700000" ixy="${reflect*-0.00068600000}" ixz="-0.00052600000" - iyy="0.00952600000" iyz="${reflect*0.00263300000}" - izz="0.00390800000"/> - </inertial> - - <visual> - <origin xyz="0 0 0.0" rpy="0 0 0" /> - <geometry> - <mesh filename="package://talos_description/meshes/v2/ankle_Y_lo_res.stl" scale="1 ${reflect*1} 1"/> - </geometry> - <material name="Grey" /> - </visual> - - <collision> - <origin xyz="0 0 0.0" rpy="0 0 0" /> - <geometry> - <mesh filename="package://talos_description/meshes/v2/ankle_Y_collision.stl" scale="1 ${reflect*1} 1"/> - </geometry> - </collision> - </link> - - <joint name="leg_${prefix}_5_joint" type="revolute"> - <parent link="leg_${prefix}_4_link"/> - <child link="leg_${prefix}_5_link"/> - <origin xyz="0.00000 0.00000 -0.32500" - rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/> - <axis xyz="0 1 0" /> - <limit lower="-1.309" upper="0.768" effort="160" velocity="5.8" /> - <dynamics friction="${leg_friction}" damping="${leg_damping}"/> - </joint> - - <!-- Joint ankle_x (mesh link) : child link None -> parent link ankle_y --> - - <link name="leg_${prefix}_6_link"> - <inertial> - <origin xyz="-0.02087 -0.00019 -0.06059" rpy="0.00000 0.00000 0.00000"/> - <mass value="1.59457"/> - <inertia ixx="0.00383800000" ixy="0.00001600000" ixz="-0.00104100000" - iyy="0.00657200000" iyz="-0.00001700000" - izz="0.00504400000"/> - </inertial> - - <visual> - <origin rpy="0 0 0" xyz="0 0 0"/> - <geometry> - <mesh filename="package://talos_description/meshes/v2/ankle_X_lo_res.stl" scale="1 ${reflect*1} 1"/> - </geometry> - <material name="Grey" /> - </visual> - - <!-- - <collision> - <origin xyz="0 0 0" rpy="0 0 0" /> - <geometry> - <mesh filename="package://talos_description/meshes/v2/ankle_X_collision.stl" scale="1 ${reflect*1} 1"/> - </geometry> - </collision> - - --> - - <collision> - <origin xyz="0 0 -0.1" rpy="0 0 0" /> - <geometry> - <box size="0.21 0.13 0.02"/> - </geometry> - </collision> - - </link> - - <joint name="leg_${prefix}_6_joint" type="revolute"> - <parent link="leg_${prefix}_5_link"/> - <child link="leg_${prefix}_6_link"/> - <origin xyz="0.00000 0.00000 0.00000" - rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/> - <axis xyz="1 0 0" /> - <limit lower="-0.5236" upper="0.5236" effort="100" velocity="4.8" /> - <dynamics friction="${leg_friction}" damping="${leg_damping}"/> - </joint> - - <!-- from here is copy paste --> - - <link name="${prefix}_sole_link"> - <inertial> - <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/> - <mass value="0.01" /> - <inertia ixx="0.0001" ixy="0.0" ixz="0.0" iyy="0.0001" iyz="0.0" izz="0.0001" /> - </inertial> - </link> - - <joint name="leg_${prefix}_sole_fix_joint" type="fixed"> - <parent link="leg_${prefix}_6_link" /> - <child link="${prefix}_sole_link" /> - <origin xyz="0.00 0.00 -0.107" rpy="0 0 0" /> - <axis xyz="1 0 0" /> - <dynamics friction="${leg_friction}" damping="${leg_damping}"/> - </joint> - - <xacro:talos_leg_simple_transmission side="${prefix}" number="1" reduction="${leg_reduction}" /> - <xacro:talos_leg_simple_transmission side="${prefix}" number="2" reduction="${leg_reduction}" /> - <xacro:talos_leg_simple_transmission side="${prefix}" number="3" reduction="${leg_reduction}" /> - <xacro:talos_leg_simple_transmission side="${prefix}" number="4" reduction="${leg_reduction}" /> - <xacro:talos_leg_simple_transmission side="${prefix}" number="5" reduction="${leg_reduction}" /> - <xacro:talos_leg_simple_transmission side="${prefix}" number="6" reduction="${leg_reduction}" /> - - <gazebo reference="leg_${prefix}_1_link"> - <mu1>0.9</mu1> - <mu2>0.9</mu2> - </gazebo> - <gazebo reference="leg_${prefix}_2_link"> - <mu1>0.9</mu1> - <mu2>0.9</mu2> - </gazebo> - <gazebo reference="leg_${prefix}_3_link"> - <mu1>0.9</mu1> - <mu2>0.9</mu2> - </gazebo> - <gazebo reference="leg_${prefix}_4_link"> - <mu1>0.9</mu1> - <mu2>0.9</mu2> - </gazebo> - <gazebo reference="leg_${prefix}_5_link"> - <mu1>0.9</mu1> - <mu2>0.9</mu2> - </gazebo> - - <!-- contact model for foot surface --> - <gazebo reference="leg_${prefix}_6_link"> - <kp>1000000.0</kp> - <kd>100.0</kd> - <mu1>1.0</mu1> - <mu2>1.0</mu2> - <fdir1>1 0 0</fdir1> - <maxVel>1.0</maxVel> - <minDepth>0.00</minDepth> - <implicitSpringDamper>1</implicitSpringDamper> - </gazebo> - - <gazebo reference="leg_${prefix}_1_joint"> - <implicitSpringDamper>1</implicitSpringDamper> - </gazebo> - <gazebo reference="leg_${prefix}_2_joint"> - <implicitSpringDamper>1</implicitSpringDamper> - </gazebo> - <gazebo reference="leg_${prefix}_3_joint"> - <implicitSpringDamper>1</implicitSpringDamper> - </gazebo> - <gazebo reference="leg_${prefix}_4_joint"> - <implicitSpringDamper>1</implicitSpringDamper> - </gazebo> - <gazebo reference="leg_${prefix}_5_joint"> - <implicitSpringDamper>1</implicitSpringDamper> - </gazebo> - <gazebo reference="leg_${prefix}_6_joint"> - <implicitSpringDamper>1</implicitSpringDamper> - <provideFeedback>1</provideFeedback> - </gazebo> - - <gazebo reference="leg_${prefix}_1_link"> - <material>Gazebo/FlatBlack</material> - </gazebo> - <gazebo reference="leg_${prefix}_2_link"> - <material>Gazebo/FlatBlack</material> - </gazebo> - <gazebo reference="leg_${prefix}_3_link"> - <material>Gazebo/FlatBlack</material> - </gazebo> - <gazebo reference="leg_${prefix}_4_link"> - <material>Gazebo/FlatBlack</material> - </gazebo> - <gazebo reference="leg_${prefix}_5_link"> - <material>Gazebo/White</material> - </gazebo> - <gazebo reference="leg_${prefix}_6_link"> - <material>Gazebo/White</material> - </gazebo> - - </xacro:macro> - -</robot> diff --git a/talos_description/urdf/sensors/back_camera.urdf.xacro b/talos_description/urdf/sensors/back_camera.urdf.xacro deleted file mode 100644 index c540ca4fa1a4dade36d07d63ceccb285850f725e..0000000000000000000000000000000000000000 --- a/talos_description/urdf/sensors/back_camera.urdf.xacro +++ /dev/null @@ -1,76 +0,0 @@ -<?xml version="1.0"?> -<!-- - - Copyright (c) 2013, PAL Robotics, S.L. - All rights reserved. - - This work is licensed under the Creative Commons Attribution-NonCommercial-NoDerivs 3.0 Unported License. - To view a copy of this license, visit http://creativecommons.org/licenses/by-nc-nd/3.0/ or send a letter to - Creative Commons, 444 Castro Street, Suite 900, Mountain View, California, 94041, USA. ---> -<robot xmlns:xacro="http://ros.org/wiki/xacro"> - - <!-- back camera macro uses stingrayf033c_camera macros --> - <xacro:include filename="$(find reemc_description)/urdf/sensors/mvbluefox_back_camera.gazebo.xacro" /> - <xacro:include filename="$(find reemc_description)/urdf/sensors/mvbluefox_camera.urdf.xacro" /> - - <!-- this macro is used for creating wide and narrow double back camera links --> - <xacro:macro name="reemc_back_camera" params="name parent focal_length hfov image_format image_width image_height *origin"> - - <joint name="${name}_frame_joint" type="fixed"> - <xacro:insert_block name="origin" /> - <parent link="${parent}"/> - <child link="${name}_link"/> - </joint> - <!-- camera link is at center of the optical frame, but in x-forward, z-upwards and y-leftwards notation (required by gazebo to simulate a camera) --> - <link name="${name}_link"> - <inertial> - <mass value="0.05" /> - <origin xyz="0 0 0" rpy="0 0 0" /> - <inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01" /> <!-- this inertia is made up for now. --> - </inertial> - - <visual> - <origin xyz="0 0 0" rpy="0 0 0" /> - <geometry> - <box size="0.001 0.001 0.001" /> - </geometry> - - </visual> - - <collision> - <origin xyz="0 0 0" rpy="0 0 0" /> - <geometry> - <box size="0.001 0.001 0.001" /> - </geometry> - </collision> - - </link> - - <!-- attach optical frame to the camera link --> - <joint name="${name}_optical_frame_joint" type="fixed"> - <origin xyz="0 0 0" rpy="${-M_PI/2} 0.0 ${-M_PI/2}" /> <!-- rotate frame from x-forward to z-forward camera coords --> - <parent link="${name}_link"/> - <child link="${name}_optical_frame"/> - </joint> - <!-- optical frame for the back camera, with z-forward notation, this is the frame back camera images users should refer to --> - <link name="${name}_optical_frame" type="camera"> - <inertial> - <mass value="0.05" /> - <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0" /> - </inertial> - </link> - - <!-- back camera --> - <xacro:mvbluefox_camera name="${name}_gazebo_back_camera" parent="${name}_link"> - <origin xyz="0 0 0" rpy="0.0 0.0 0.0" /> - </xacro:mvbluefox_camera> - - <!-- Back camera Gazebo simulation --> - <xacro:mvbluefox_back_camera_gazebo name="${name}" image_format="${image_format}" - hfov="${hfov}" focal_length="${focal_length}" - frame_id="${name}_optical_frame" - image_width="${image_width}" image_height="${image_height}"/> - - </xacro:macro> -</robot> diff --git a/talos_description/urdf/sensors/laser.gazebo.xacro b/talos_description/urdf/sensors/laser.gazebo.xacro deleted file mode 100644 index 7e06f1e22bc60723086381ee057e87bc7cc6dd6e..0000000000000000000000000000000000000000 --- a/talos_description/urdf/sensors/laser.gazebo.xacro +++ /dev/null @@ -1,50 +0,0 @@ -<?xml version="1.0"?> -<!-- - - Copyright (c) 2011, PAL Robotics, S.L. - All rights reserved. - - This work is licensed under the Creative Commons Attribution-NonCommercial-NoDerivs 3.0 Unported License. - To view a copy of this license, visit http://creativecommons.org/licenses/by-nc-nd/3.0/ or send a letter to - Creative Commons, 444 Castro Street, Suite 900, Mountain View, California, 94041, USA. ---> -<robot xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor" - xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller" - xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface" - xmlns:xacro="http://ros.org/wiki/xacro"> - -<xacro:macro name="reemc_laser_gazebo" params="name ros_topic update_rate min_angle max_angle nrays"> - <gazebo reference="${name}_link"> - <sensor type="ray" name="${name}_sensor"> - <pose>0 0 0 0 0 0</pose> - <visualize>false</visualize> - <update_rate>${update_rate}</update_rate> - <ray> - <scan> - <horizontal> - <samples>${nrays}</samples> - <resolution>1</resolution> - <min_angle>${min_angle}</min_angle> - <max_angle>${max_angle}</max_angle> - </horizontal> - </scan> - <range> - <min>0.02</min> - <max>5.6</max> - <resolution>0.01</resolution> - </range> - </ray> - <plugin filename="libgazebo_ros_laser.so" name="gazebo_ros_laser" > - <frameName>/${name}_link</frameName> - <topicName>${ros_topic}</topicName> - <gaussianNoise>0.03</gaussianNoise> - <hokuyoMinIntensity>101</hokuyoMinIntensity> - <updateRate>${update_rate}</updateRate> - <alwaysOn>true</alwaysOn> - </plugin> - </sensor> - </gazebo> -</xacro:macro> - - -</robot> diff --git a/talos_description/urdf/sensors/laser.urdf.xacro b/talos_description/urdf/sensors/laser.urdf.xacro deleted file mode 100644 index 121e66a8f59c5bd554e6e22aa080b2cd3c6d2515..0000000000000000000000000000000000000000 --- a/talos_description/urdf/sensors/laser.urdf.xacro +++ /dev/null @@ -1,47 +0,0 @@ -<?xml version="1.0"?> -<!-- - - Copyright (c) 2011, PAL Robotics, S.L. - All rights reserved. - - This work is licensed under the Creative Commons Attribution-NonCommercial-NoDerivs 3.0 Unported License. - To view a copy of this license, visit http://creativecommons.org/licenses/by-nc-nd/3.0/ or send a letter to - Creative Commons, 444 Castro Street, Suite 900, Mountain View, California, 94041, USA. ---> -<robot xmlns:xacro="http://ros.org/wiki/xacro"> - - <xacro:include filename="$(find reemc_description)/urdf/sensors/laser.gazebo.xacro" /> - - <xacro:macro name="reemc_laser" params="name parent *origin ros_topic update_rate min_angle max_angle nrays"> - - <link name="${name}_link"> - <inertial> - <origin xyz="0.0 0.0 0.0" rpy="0 0 0" /> - <mass value="0.001" /> - <inertia iyy="4.2412E-05" ixy="4.9927E-08" iyz="-9.8165E-09" ixx="3.7174E-05" ixz="1.1015E-05" izz="4.167E-05" /> - </inertial> - <!-- <visual> - <origin xyz="0.0 0 0.05" rpy="0 0 ${90.0*deg_to_rad}" /> - <geometry> - <mesh filename="package://reemc_description/meshes/sensors/urg-04lx-ug01.stl" scale="0.001 0.001 0.001"/> - </geometry> - <material name="DarkGrey" /> - </visual> - --> - </link> - - <joint name="${name}_joint" type="fixed"> - <axis xyz="0 1 0" /> - <xacro:insert_block name="origin" /> - <parent link="${parent}"/> - <child link="${name}_link"/> - <dynamics friction="1.0" damping="1"/> - <limit lower="0" upper="0" effort="60" velocity="20" /> - </joint> - - <!-- gazebo extensions --> - <xacro:reemc_laser_gazebo name="${name}" ros_topic="${ros_topic}" update_rate="${update_rate}" min_angle="${min_angle}" max_angle="${max_angle}" nrays="${nrays}"/> - - </xacro:macro> - -</robot> diff --git a/talos_description/urdf/sensors/mvbluefox_back_camera.gazebo.xacro b/talos_description/urdf/sensors/mvbluefox_back_camera.gazebo.xacro deleted file mode 100644 index 8765c11b88e5d942378992e67d9112e1507c559c..0000000000000000000000000000000000000000 --- a/talos_description/urdf/sensors/mvbluefox_back_camera.gazebo.xacro +++ /dev/null @@ -1,60 +0,0 @@ -<?xml version="1.0"?> -<!-- - - Copyright (c) 2013, PAL Robotics, S.L. - All rights reserved. - - This work is licensed under the Creative Commons Attribution-NonCommercial-NoDerivs 3.0 Unported License. - To view a copy of this license, visit http://creativecommons.org/licenses/by-nc-nd/3.0/ or send a letter to - Creative Commons, 444 Castro Street, Suite 900, Mountain View, California, 94041, USA. ---> -<robot name="reemc" xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor" - xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller" - xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface" - xmlns:xacro="http://ros.org/wiki/xacro"> - - <xacro:macro name="mvbluefox_back_camera_gazebo" params="name image_format hfov focal_length frame_id image_width image_height"> - - <gazebo reference="${name}_link"> - - <sensor type="camera" name="gazebo_${name}_camera"> - <update_rate>15.0</update_rate> - <camera> - <horizontal_fov>${ hfov }</horizontal_fov> - <image> - <width>${image_width} </width> - <height> ${image_height}</height> - <format>${image_format}</format> - </image> - <clip> - <near>0.01</near> - <far>100</far> - </clip> - </camera> - <plugin name="monocular_camera_controller" filename="libgazebo_ros_camera.so"> - <alwaysOn>true</alwaysOn> - <updateRate>15.0</updateRate> - <cameraName>${name}</cameraName> - <imageTopicName>image</imageTopicName> - <cameraInfoTopicName>camera_info</cameraInfoTopicName> - <frameName>${frame_id}</frameName> - <hackBaseline>0</hackBaseline> - <CxPrime>${(image_width+1)/2}</CxPrime> - <Cx>${(image_width+1)/2}</Cx> - <Cy>${(image_height+1)/2}</Cy> - <focalLength>${focal_length}</focalLength> <!-- image_width / (2*tan(hfov_radian /2)) --> - <distalostionK1>0.0</distalostionK1> - <distalostionK2>0.0</distalostionK2> - <distalostionK3>0.0</distalostionK3> - <distalostionT1>0.0</distalostionT1> - <distalostionT2>0.0</distalostionT2> - </plugin> - </sensor> - - </gazebo> - </xacro:macro> - -</robot> - - - diff --git a/talos_description/urdf/sensors/mvbluefox_camera.urdf.xacro b/talos_description/urdf/sensors/mvbluefox_camera.urdf.xacro deleted file mode 100644 index d48d3e3e3a79102b369e8938832bb0fe3a2acdb0..0000000000000000000000000000000000000000 --- a/talos_description/urdf/sensors/mvbluefox_camera.urdf.xacro +++ /dev/null @@ -1,41 +0,0 @@ -<?xml version="1.0"?> -<!-- - - Copyright (c) 2013, PAL Robotics, S.L. - All rights reserved. - - This work is licensed under the Creative Commons Attribution-NonCommercial-NoDerivs 3.0 Unported License. - To view a copy of this license, visit http://creativecommons.org/licenses/by-nc-nd/3.0/ or send a letter to - Creative Commons, 444 Castro Street, Suite 900, Mountain View, California, 94041, USA. ---> -<!-- XML namespaces --> -<robot name="reemc" xmlns:xacro="http://ros.org/wiki/xacro"> - - <xacro:macro name="mvbluefox_camera" params="name parent *origin"> - - <joint name="${name}_frame_joint" type="fixed"> - <xacro:insert_block name="origin" /> - <parent link="${parent}"/> - <child link="${name}_link"/> - </joint> - - <link name="${name}_link"> - <inertial> - <mass value="0.1" /> - <origin xyz="0 0 0" /> - <inertia ixx="0" ixy="0.0" ixz="0.0" - iyy="0" iyz="0.0" - izz="0" /> - </inertial> - <visual> - <origin xyz="-0.01 0 0" rpy="0 ${deg_to_rad * 90} 0" /> - <geometry> - <cylinder radius="0.01" length="0.02" /> - </geometry> - <material name="Blue"/> - </visual> - </link> - - </xacro:macro> - -</robot> diff --git a/talos_description/urdf/sensors/prosilicaGC655C_camera.urdf.xacro b/talos_description/urdf/sensors/prosilicaGC655C_camera.urdf.xacro deleted file mode 100644 index 4499bcde87e365c61e8dc50dfdaf5ebe92bb2e09..0000000000000000000000000000000000000000 --- a/talos_description/urdf/sensors/prosilicaGC655C_camera.urdf.xacro +++ /dev/null @@ -1,40 +0,0 @@ -<?xml version="1.0"?> -<!-- - - Copyright (c) 2013, PAL Robotics, S.L. - All rights reserved. - - This work is licensed under the Creative Commons Attribution-NonCommercial-NoDerivs 3.0 Unported License. - To view a copy of this license, visit http://creativecommons.org/licenses/by-nc-nd/3.0/ or send a letter to - Creative Commons, 444 Castro Street, Suite 900, Mountain View, California, 94041, USA. ---> -<!-- XML namespaces --> -<robot name="reemc" xmlns:xacro="http://ros.org/wiki/xacro"> - <xacro:macro name="prosilicaGC655C_camera" params="name parent *origin"> - - <joint name="${name}_frame_joint" type="fixed"> - <xacro:insert_block name="origin" /> - <parent link="${parent}"/> - <child link="${name}_link"/> - </joint> - - <link name="${name}_link"> - <inertial> - <mass value="0.1" /> - <origin xyz="0 0 0" /> - <inertia ixx="0" ixy="0.0" ixz="0.0" - iyy="0" iyz="0.0" - izz="0" /> - </inertial> - <visual> - <origin xyz="-0.01 0 0" rpy="0 ${deg_to_rad * 90} 0" /> - <geometry> - <cylinder radius="0.01" length="0.018" /> - </geometry> - <material name="Blue"/> - </visual> - </link> - - </xacro:macro> - -</robot> diff --git a/talos_description/urdf/sensors/prosilica_stereo_camera.gazebo.xacro b/talos_description/urdf/sensors/prosilica_stereo_camera.gazebo.xacro deleted file mode 100644 index abfd2748d2dd73c906aca6003225c5fd9bee5ed9..0000000000000000000000000000000000000000 --- a/talos_description/urdf/sensors/prosilica_stereo_camera.gazebo.xacro +++ /dev/null @@ -1,67 +0,0 @@ -<?xml version="1.0"?> -<!-- - - Copyright (c) 2013, PAL Robotics, S.L. - All rights reserved. - - This work is licensed under the Creative Commons Attribution-NonCommercial-NoDerivs 3.0 Unported License. - To view a copy of this license, visit http://creativecommons.org/licenses/by-nc-nd/3.0/ or send a letter to - Creative Commons, 444 Castro Street, Suite 900, Mountain View, California, 94041, USA. ---> -<robot name="reemc" xmlns:xacro="http://ros.org/wiki/xacro"> - - <xacro:macro name="prosilica_stereo_camera_gazebo" params="name image_format hfov focal_length frame_id hack_baseline image_width image_height"> - <gazebo reference="${name}_link"> - - <sensor type="multicamera" name="gazebo_${name}_camera"> - <update_rate>25.0</update_rate> - <camera name="left"> - <horizontal_fov>${ hfov }</horizontal_fov> - <image> - <width>${image_width} </width> - <height> ${image_height}</height> - <format>${image_format}</format> - </image> - <clip> - <near>0.01</near> - <far>100</far> - </clip> - </camera> - <camera name="right"> - <pose>0 -${hack_baseline} 0 0 0 0</pose> <!-- the pose is wrt /stereo_link which is the parent of stereo_optical_frame --> - <horizontal_fov>${ hfov }</horizontal_fov> - <image> - <width>${image_width} </width> - <height> ${image_height}</height> - <format>${image_format}</format> - </image> - <clip> - <near>0.01</near> - <far>100</far> - </clip> - </camera> - <plugin name="stereo_camera_controller" filename="libgazebo_ros_multicamera.so"> - <alwaysOn>true</alwaysOn> - <updateRate>25.0</updateRate> - <cameraName>${name}</cameraName> - <imageTopicName>image</imageTopicName> - <cameraInfoTopicName>camera_info</cameraInfoTopicName> - <frameName>${frame_id}</frameName> - <hackBaseline>${hack_baseline}</hackBaseline> - <CxPrime>${(image_width+1)/2}</CxPrime> - <Cx>${(image_width+1)/2}</Cx> - <Cy>${(image_height+1)/2}</Cy> - <focalLength>${focal_length}</focalLength> <!-- image_width / (2*tan(hfov_radian /2)) --> - <distalostionK1>0.0</distalostionK1> - <distalostionK2>0.0</distalostionK2> - <distalostionK3>0.0</distalostionK3> - <distalostionT1>0.0</distalostionT1> - <distalostionT2>0.0</distalostionT2> - </plugin> - </sensor> - </gazebo> - </xacro:macro> -</robot> - - - diff --git a/talos_description/urdf/sensors/range.gazebo.xacro b/talos_description/urdf/sensors/range.gazebo.xacro deleted file mode 100644 index 73806ef3968f1caa27ea2275823051418c284061..0000000000000000000000000000000000000000 --- a/talos_description/urdf/sensors/range.gazebo.xacro +++ /dev/null @@ -1,56 +0,0 @@ -<?xml version="1.0"?> - -<!-- - Copyright (c) 2011, PAL Robotics, S.L. - All rights reserved. - - This work is licensed under the Creative Commons Attribution-NonCommercial-NoDerivs 3.0 Unported License. - To view a copy of this license, visit http://creativecommons.org/licenses/by-nc-nd/3.0/ or send a letter to - Creative Commons, 444 Castro Street, Suite 900, Mountain View, California, 94041, USA. ---> - -<robot xmlns:xacro="http://ros.org/wiki/xacro"> - - <xacro:macro name="range_reem_gazebo" params="name ros_topic update_rate maxRange minRange fov radiation" > - <gazebo reference="${name}_link"> - <sensor type="ray" name="${name}"> - <pose>0 0 0 0 0 0</pose> - <update_rate>${update_rate}</update_rate> - <visualize>false</visualize> - <ray> - <scan> - <horizontal> - <samples>5</samples> - <resolution>1</resolution> - <min_angle>-${fov/2}</min_angle> - <max_angle>${fov/2}</max_angle> - </horizontal> - <vertical> - <samples>5</samples> - <resolution>1</resolution> - <min_angle>-${fov/2}</min_angle> - <max_angle>${fov/2}</max_angle> - </vertical> - </scan> - <range> - <min>${minRange}</min> - <max>${maxRange}</max> - <resolution>0.01</resolution> - </range> - </ray> - <plugin filename="libgazebo_ros_range.so" name="gazebo_ros_range"> - <gaussianNoise>0.005</gaussianNoise> - <alwaysOn>true</alwaysOn> - <updateRate>${update_rate}</updateRate> - <topicName>${ros_topic}</topicName> - <frameName>${name}_link</frameName> - <minRange>${minRange}</minRange> - <maxRange>${maxRange}</maxRange> - <fov>${fov}</fov> - <radiation>${radiation}</radiation> - </plugin> - </sensor> - </gazebo> - </xacro:macro> - -</robot> diff --git a/talos_description/urdf/sensors/range.urdf.xacro b/talos_description/urdf/sensors/range.urdf.xacro deleted file mode 100644 index 52bdd86165f835de59177f932f45506b37c251e5..0000000000000000000000000000000000000000 --- a/talos_description/urdf/sensors/range.urdf.xacro +++ /dev/null @@ -1,36 +0,0 @@ -<?xml version="1.0"?> - -<!-- - Copyright (c) 2011, PAL Robotics, S.L. - All rights reserved. - - This work is licensed under the Creative Commons Attribution-NonCommercial-NoDerivs 3.0 Unported License. - To view a copy of this license, visit http://creativecommons.org/licenses/by-nc-nd/3.0/ or send a letter to - Creative Commons, 444 Castro Street, Suite 900, Mountain View, California, 94041, USA. ---> - -<robot xmlns:xacro="http://ros.org/wiki/xacro"> - - <xacro:include filename="$(find reemc_description)/urdf/sensors/range.gazebo.xacro" /> - - <xacro:macro name="range_reem" params="name parent *origin ros_topic update_rate maxRange minRange fov radiation"> - - <link name="${name}_link"> - <inertial> - <mass value="0.001" /> - <origin xyz="0 0 0" rpy="0 0 0" /> - <inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.000001" iyz="0" izz="0.0001" /> - </inertial> - </link> - - <joint name="${name}_joint" type="fixed"> - <xacro:insert_block name="origin" /> - <axis xyz="0 0 1"/> - <parent link="${parent}_link"/> - <child link="${name}_link"/> - </joint> - - <!-- gazebo extensions --> - <xacro:range_reem_gazebo name="${name}" ros_topic="${ros_topic}" update_rate="${update_rate}" maxRange="${maxRange}" minRange="${minRange}" fov="${fov}" radiation="${radiation}"/> - </xacro:macro> -</robot> diff --git a/talos_description/urdf/sensors/stereo_camera.gazebo.xacro b/talos_description/urdf/sensors/stereo_camera.gazebo.xacro deleted file mode 100644 index 8e8b59df5a9d9932cfdf5ee53069ec752d2f4f81..0000000000000000000000000000000000000000 --- a/talos_description/urdf/sensors/stereo_camera.gazebo.xacro +++ /dev/null @@ -1,28 +0,0 @@ -<?xml version="1.0"?> -<!-- - - Copyright (c) 2011, PAL Robotics, S.L. - All rights reserved. - - This work is licensed under the Creative Commons Attribution-NonCommercial-NoDerivs 3.0 Unported License. - To view a copy of this license, visit http://creativecommons.org/licenses/by-nc-nd/3.0/ or send a letter to - Creative Commons, 444 Castro Street, Suite 900, Mountain View, California, 94041, USA. ---> -<robot name="reemc" xmlns:xacro="http://ros.org/wiki/xacro"> - - <!-- this macro is used for creating wide and narrow double stereo camera in simulation --> - <xacro:macro name="stereo_camera_gazebo_v0" params="name focal_length_left hfov_left focal_length_right hfov_right image_width image_height"> - - <gazebo reference="${name}_link"> - <material value="White"/> - <gravity value="false"/> - </gazebo> - - <gazebo reference="${name}_optical_frame"> - <material value="White"/> - <gravity value="false"/> - </gazebo> - - </xacro:macro> - -</robot> diff --git a/talos_description/urdf/sensors/stereo_camera.urdf.xacro b/talos_description/urdf/sensors/stereo_camera.urdf.xacro deleted file mode 100644 index 9f5f741d757c98fd8e90fbc0475c0968dc1396cb..0000000000000000000000000000000000000000 --- a/talos_description/urdf/sensors/stereo_camera.urdf.xacro +++ /dev/null @@ -1,94 +0,0 @@ -<?xml version="1.0"?> -<!-- - - Copyright (c) 2014, PAL Robotics, S.L. - All rights reserved. - - This work is licensed under the Creative Commons Attribution-NonCommercial-NoDerivs 3.0 Unported License. - To view a copy of this license, visit http://creativecommons.org/licenses/by-nc-nd/3.0/ or send a letter to - Creative Commons, 444 Castro Street, Suite 900, Mountain View, California, 94041, USA. ---> -<robot name="reemc" xmlns:xacro="http://ros.org/wiki/xacro"> - - <xacro:include filename="$(find reemc_description)/urdf/sensors/prosilica_stereo_camera.gazebo.xacro" /> - <xacro:include filename="$(find reemc_description)/urdf/sensors/prosilicaGC655C_camera.urdf.xacro" /> - - <xacro:property name="stereo_dx" value="0.00" /> - <xacro:property name="stereo_dy" value="-0.073" /> <!-- stereo baseline according to base_link which has X pointing forward, Y leftwards and Z upwards (required by Gazebo for a camera sensor) --> - <xacro:property name="stereo_dz" value="0.00" /> - <xacro:property name="stereo_rx" value="0.00" /> - <xacro:property name="stereo_ry" value="0.00" /> - <xacro:property name="stereo_rz" value="0.00" /> - - <!-- this macro is used for creating wide and narrow double stereo camera links --> - <xacro:macro name="reemc_stereo_camera" params="name parent focal_length hfov image_format image_width image_height *origin"> - - <joint name="${name}_frame_joint" type="fixed"> - <xacro:insert_block name="origin" /> - <parent link="${parent}"/> - <child link="${name}_link"/> - </joint> - <!-- camera link is at center of the optical frame, but in x-forward, z-upwards and y-leftwards notation (required by gazebo to simulate a camera) --> - <link name="${name}_link"> - <inertial> - <mass value="0.01" /> - <origin xyz="0 0 0" rpy="0 0 0" /> - <inertia ixx="0" ixy="0" ixz="0" - iyy="0" iyz="0" - izz="0" /> <!-- this inertia is made up for now. --> - </inertial> - - <visual> - <origin xyz="0 0 0" rpy="0 0 0" /> - <geometry> - <box size="0.001 0.001 0.001" /> - </geometry> - <material name="Blue"/> - </visual> - - <collision> - <origin xyz="0 0 0" rpy="0 0 0" /> - <geometry> - <box size="0.001 0.001 0.001" /> - </geometry> - </collision> - - </link> - - <!-- attach optical frame to the camera link --> - <joint name="${name}_optical_frame_joint" type="fixed"> - <origin xyz="0 0 0" rpy="${-M_PI/2} 0.0 ${-M_PI/2}" /> <!-- rotate frame from x-forward to z-forward camera coords --> - <parent link="${name}_link"/> - <child link="${name}_optical_frame"/> - </joint> - <!-- optical frame for the stereo camera, with z-forward notation, this is the frame stereo camera images users should refer to --> - <link name="${name}_optical_frame" type="camera"> - <inertial> - <mass value="0.01" /> - <origin xyz="0 0 0" rpy="0 0 0" /> - <inertia ixx="0" ixy="0" ixz="0" - iyy="0" iyz="0" - izz="0" /> <!-- this inertia is made up for now. --> - </inertial> - </link> - - <!-- stereo left camera --> - <xacro:prosilicaGC655C_camera name="${name}_gazebo_left_camera" parent="${name}_link"> - <origin xyz="0 0 0" rpy="0.0 0.0 0.0" /> - </xacro:prosilicaGC655C_camera> - - <!-- stereo right camera --> - <xacro:prosilicaGC655C_camera name="${name}_gazebo_right_camera" parent="${name}_link"> - <origin xyz="${stereo_dx} ${stereo_dy} ${stereo_dz}" rpy="${stereo_rx} ${stereo_ry} ${stereo_rz}" /> - </xacro:prosilicaGC655C_camera> - - - <!-- Stereo camera Gazebo simulation --> - <xacro:prosilica_stereo_camera_gazebo name="${name}" image_format="${image_format}" - hfov="${hfov}" focal_length="${focal_length}" - frame_id="${name}_optical_frame" hack_baseline="${-stereo_dy}" - image_width="${image_width}" image_height="${image_height}"/> - - - </xacro:macro> -</robot>