diff --git a/talos_description/gazebo/gazebo.urdf.xacro b/talos_description/gazebo/gazebo.urdf.xacro index 79b80b7e1ea52b8ae46f5d5ed67841345507532b..916a7dc2b37c47e293baa7115ec0d41d4270547b 100644 --- a/talos_description/gazebo/gazebo.urdf.xacro +++ b/talos_description/gazebo/gazebo.urdf.xacro @@ -1,6 +1,6 @@ <?xml version="1.0"?> -<robot name="starleth"> +<robot name="talos"> <gazebo> <plugin filename="libgazebo_ros_control.so" name="gazebo_ros_control"> <ns></ns> @@ -12,7 +12,7 @@ <gazebo> <plugin filename="libgazebo_world_odometry.so" name="gazebo_ros_odometry"> - <frameName>talos_2_link</frameName> + <frameName>torso_2_link</frameName> <topicName>floating_base_pose</topicName> </plugin> </gazebo> @@ -82,7 +82,7 @@ </gazebo> <!-- define global properties --> - <property name="M_PI" value="3.1415926535897931" /> + <!-- <xacro:property name="M_PI" value="3.1415926535897931" /> --> </robot> diff --git a/talos_description/meshes/torso/base_link.STL b/talos_description/meshes/torso/base_link.STL new file mode 100644 index 0000000000000000000000000000000000000000..38e248ce7a00679aca49d0be7a869e30ad9ca807 Binary files /dev/null and b/talos_description/meshes/torso/base_link.STL differ diff --git a/talos_description/meshes/torso/base_link_collision.STL b/talos_description/meshes/torso/base_link_collision.STL new file mode 100644 index 0000000000000000000000000000000000000000..c5004ceb7ee8e7afcf9678941a3cba7c03655d04 Binary files /dev/null and b/talos_description/meshes/torso/base_link_collision.STL differ diff --git a/talos_description/meshes/torso/torso_2.STL b/talos_description/meshes/torso/torso_2.STL new file mode 100644 index 0000000000000000000000000000000000000000..ec8b51a60f800c301f26da8e721f49aa4f271205 Binary files /dev/null and b/talos_description/meshes/torso/torso_2.STL differ diff --git a/talos_description/meshes/torso/torso_2_collision.STL b/talos_description/meshes/torso/torso_2_collision.STL new file mode 100644 index 0000000000000000000000000000000000000000..44f199081dfd9cd7665254f49723e43571726639 Binary files /dev/null and b/talos_description/meshes/torso/torso_2_collision.STL differ diff --git a/talos_description/meshes/torso/toso_1.STL b/talos_description/meshes/torso/toso_1.STL new file mode 100644 index 0000000000000000000000000000000000000000..f7418ca280b5a368c02ebf15c71d034eb475d44f Binary files /dev/null and b/talos_description/meshes/torso/toso_1.STL differ diff --git a/talos_description/robots/talos_full.urdf.xacro b/talos_description/robots/talos_full.urdf.xacro index c85595c8fe8466d5fb998b40119ddd9e8663f245..633285900d459c0f5998a59c425a3015348272c7 100644 --- a/talos_description/robots/talos_full.urdf.xacro +++ b/talos_description/robots/talos_full.urdf.xacro @@ -20,7 +20,7 @@ <xacro:include filename="$(find talos_description)/urdf/gripper/gripper.urdf.xacro" /> <xacro:include filename="$(find talos_description)/urdf/leg/leg_v2.urdf.xacro" /> - <xacro:talos_talos name="talos" /> + <xacro:talos_torso name="torso" /> <xacro:talos_head name="head" parent="torso_2_link"/> diff --git a/talos_description/robots/talos_torso.urdf.xacro b/talos_description/robots/talos_torso.urdf.xacro index e6df79b08064215288f5686d8032034573afd38a..05a70cce3f4c69b493965e4de84e11acac4692cd 100644 --- a/talos_description/robots/talos_torso.urdf.xacro +++ b/talos_description/robots/talos_torso.urdf.xacro @@ -13,9 +13,9 @@ 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/talos/talos.urdf.xacro" /> + <xacro:include filename="$(find talos_description)/urdf/torso/torso.urdf.xacro" /> - <xacro:talos_talos name="talos" /> + <xacro:talos_torso name="torso" /> <!-- Generic simulatalos_gazebo plugins --> <xacro:include filename="$(find talos_description)/gazebo/gazebo.urdf.xacro" /> diff --git a/talos_description/robots/upload_talos.launch b/talos_description/robots/upload_talos.launch index 0bda81247edd6bc4a909bef0e17a5dfa486e4a65..99f7ba8307f7456fb255bcc8608f0fbdd672efb2 100644 --- a/talos_description/robots/upload_talos.launch +++ b/talos_description/robots/upload_talos.launch @@ -1,6 +1,6 @@ <launch> <!-- Robot description --> - <param name="robot_description" command="$(find xacro)/xacro.py '$(find talos_description)/robots/talos_talos.urdf.xacro'" /> + <param name="robot_description" command="$(find xacro)/xacro.py '$(find talos_description)/robots/talos_torso.urdf.xacro'" /> </launch> diff --git a/talos_description/urdf/deg_to_rad.xacro b/talos_description/urdf/deg_to_rad.xacro index a662ea2ac383747232abbddd6ec6948c65b816c6..2f35e1cca1164f049ff3c02e3ee9749caef2a07b 100644 --- a/talos_description/urdf/deg_to_rad.xacro +++ b/talos_description/urdf/deg_to_rad.xacro @@ -1,5 +1,5 @@ <robot xmlns:xacro="http://ros.org/wiki/xacro"> - <property name="deg_to_rad" value="0.01745329251994329577" /> + <xacro:property name="deg_to_rad" value="0.01745329251994329577" /> </robot> diff --git a/talos_description/urdf/sensors/back_camera.urdf.xacro b/talos_description/urdf/sensors/back_camera.urdf.xacro index 39b7656beaff0e07a141d3cfdeb54af4591f4fbc..c540ca4fa1a4dade36d07d63ceccb285850f725e 100644 --- a/talos_description/urdf/sensors/back_camera.urdf.xacro +++ b/talos_description/urdf/sensors/back_camera.urdf.xacro @@ -18,7 +18,7 @@ <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"> - <insert_block name="origin" /> + <xacro:insert_block name="origin" /> <parent link="${parent}"/> <child link="${name}_link"/> </joint> diff --git a/talos_description/urdf/sensors/calibration.xacro b/talos_description/urdf/sensors/calibration.xacro index 884ff295a45aa897829603c22cac7fe0c0f66169..55f7e73a93f2e06e2d6f4ee6db8e98aa1ceea80e 100644 --- a/talos_description/urdf/sensors/calibration.xacro +++ b/talos_description/urdf/sensors/calibration.xacro @@ -13,18 +13,18 @@ --> <robot> - <property name="M_PI" value="3.1415926535897931" /> + <xacro:property name="M_PI" value="3.1415926535897931" /> <!-- Head-mounted ASUS Xtion Pro Live --> <!-- These calibration values affect 2 frames: (name)_xtion_ir_optical_frame (name)_xtion_rgb_optical_frame --> - <property name="cal_head_mount_xtion_x" value="0.0" /> - <property name="cal_head_mount_xtion_y" value="0.0" /> - <property name="cal_head_mount_xtion_z" value="0.0" /> - <property name="cal_head_mount_xtion_roll" value="0.0" /> - <property name="cal_head_mount_xtion_pitch" value="0.0" /> - <property name="cal_head_mount_xtion_yaw" value="0.0" /> + <xacro:property name="cal_head_mount_xtion_x" value="0.0" /> + <xacro:property name="cal_head_mount_xtion_y" value="0.0" /> + <xacro:property name="cal_head_mount_xtion_z" value="0.0" /> + <xacro:property name="cal_head_mount_xtion_roll" value="0.0" /> + <xacro:property name="cal_head_mount_xtion_pitch" value="0.0" /> + <xacro:property name="cal_head_mount_xtion_yaw" value="0.0" /> </robot> diff --git a/talos_description/urdf/sensors/imu.urdf.xacro b/talos_description/urdf/sensors/imu.urdf.xacro index 05bd32c9e994302559ea7f39cdbc9c32e8be0c40..e88fe1b5cea31a32e672afcfbcfcd9e21d02c808 100644 --- a/talos_description/urdf/sensors/imu.urdf.xacro +++ b/talos_description/urdf/sensors/imu.urdf.xacro @@ -24,7 +24,7 @@ </visual> </link> <joint name="imu_joint" type="fixed"> - <insert_block name="origin"/> + <xacro:insert_block name="origin"/> <parent link="${parent}"/> <child link="${name}_link"/> </joint> diff --git a/talos_description/urdf/sensors/laser.urdf.xacro b/talos_description/urdf/sensors/laser.urdf.xacro index 67b639e4bbecf89e9b5dc3bce27ee5afde16c0c0..121e66a8f59c5bd554e6e22aa080b2cd3c6d2515 100644 --- a/talos_description/urdf/sensors/laser.urdf.xacro +++ b/talos_description/urdf/sensors/laser.urdf.xacro @@ -32,7 +32,7 @@ <joint name="${name}_joint" type="fixed"> <axis xyz="0 1 0" /> - <insert_block name="origin" /> + <xacro:insert_block name="origin" /> <parent link="${parent}"/> <child link="${name}_link"/> <dynamics friction="1.0" damping="1"/> diff --git a/talos_description/urdf/sensors/mvbluefox_camera.urdf.xacro b/talos_description/urdf/sensors/mvbluefox_camera.urdf.xacro index f9b1042695a7a3f94179e9c8a77cfdfdf10cf0cb..d48d3e3e3a79102b369e8938832bb0fe3a2acdb0 100644 --- a/talos_description/urdf/sensors/mvbluefox_camera.urdf.xacro +++ b/talos_description/urdf/sensors/mvbluefox_camera.urdf.xacro @@ -14,7 +14,7 @@ <xacro:macro name="mvbluefox_camera" params="name parent *origin"> <joint name="${name}_frame_joint" type="fixed"> - <insert_block name="origin" /> + <xacro:insert_block name="origin" /> <parent link="${parent}"/> <child link="${name}_link"/> </joint> diff --git a/talos_description/urdf/sensors/orbbec_astra_pro.urdf.xacro b/talos_description/urdf/sensors/orbbec_astra_pro.urdf.xacro index 81a7f457ac0d4b8fbb02ace500435f1638128950..f86315999ecb2490bfadbce5372866129348d2b7 100644 --- a/talos_description/urdf/sensors/orbbec_astra_pro.urdf.xacro +++ b/talos_description/urdf/sensors/orbbec_astra_pro.urdf.xacro @@ -31,7 +31,7 @@ <!-- frames in the center of the camera --> <joint name="${name}_joint" type="fixed"> - <insert_block name="origin"/> + <xacro:insert_block name="origin"/> <axis xyz="0 0 1"/> <!-- <limit lower="0" upper="0.001" effort="100" velocity="0.01"/> --> <parent link="${parent}_link"/> @@ -65,7 +65,7 @@ </link> <joint name="${name}_optical_joint" type="fixed"> - <insert_block name="optical_origin" /> + <xacro:insert_block name="optical_origin" /> <parent link="${name}_link"/> <child link="${name}_optical_frame"/> </joint> diff --git a/talos_description/urdf/sensors/prosilicaGC655C_camera.urdf.xacro b/talos_description/urdf/sensors/prosilicaGC655C_camera.urdf.xacro index 8134fa6e590abd087e14b6be1d12d8e7eae8a71a..d46075ff0b4b8deb3a86d9279a165ba2b62cd95a 100644 --- a/talos_description/urdf/sensors/prosilicaGC655C_camera.urdf.xacro +++ b/talos_description/urdf/sensors/prosilicaGC655C_camera.urdf.xacro @@ -13,7 +13,7 @@ <xacro:macro name="prosilicaGC655C_camera" params="name parent *origin"> <joint name="${name}_frame_joint" type="fixed"> - <insert_block name="origin" /> + <xacro:insert_block name="origin" /> <parent link="${parent}"/> <child link="${name}_link"/> </joint> diff --git a/talos_description/urdf/sensors/range.urdf.xacro b/talos_description/urdf/sensors/range.urdf.xacro index c9177fc4b41f1f9c52c6402696754efcc1e38d92..52bdd86165f835de59177f932f45506b37c251e5 100644 --- a/talos_description/urdf/sensors/range.urdf.xacro +++ b/talos_description/urdf/sensors/range.urdf.xacro @@ -24,7 +24,7 @@ </link> <joint name="${name}_joint" type="fixed"> - <insert_block name="origin" /> + <xacro:insert_block name="origin" /> <axis xyz="0 0 1"/> <parent link="${parent}_link"/> <child link="${name}_link"/> diff --git a/talos_description/urdf/sensors/stereo_camera.urdf.xacro b/talos_description/urdf/sensors/stereo_camera.urdf.xacro index bfbb3efd9085090ce711e7e6d5b5d3e61f5614c7..9f5f741d757c98fd8e90fbc0475c0968dc1396cb 100644 --- a/talos_description/urdf/sensors/stereo_camera.urdf.xacro +++ b/talos_description/urdf/sensors/stereo_camera.urdf.xacro @@ -13,18 +13,18 @@ <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" /> - <property name="stereo_dx" value="0.00" /> - <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) --> - <property name="stereo_dz" value="0.00" /> - <property name="stereo_rx" value="0.00" /> - <property name="stereo_ry" value="0.00" /> - <property name="stereo_rz" value="0.00" /> + <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"> - <insert_block name="origin" /> + <xacro:insert_block name="origin" /> <parent link="${parent}"/> <child link="${name}_link"/> </joint> diff --git a/talos_description/urdf/sensors/xtion_pro_live.urdf.xacro b/talos_description/urdf/sensors/xtion_pro_live.urdf.xacro index 1ac27d4130dc7064d3f48cec0ef71fa43955fd20..cb6464d5bea2fa9e2ba762ad06f6f550c7714ba4 100644 --- a/talos_description/urdf/sensors/xtion_pro_live.urdf.xacro +++ b/talos_description/urdf/sensors/xtion_pro_live.urdf.xacro @@ -27,13 +27,13 @@ <xacro:include filename="$(find reemc)/urdf/sensors/calibration.xacro" /> <xacro:include filename="$(find reemc)/urdf/sensors/openni.gazebo.xacro" /> - <property name="M_PI" value="3.1415926535897931" /> + <xacro:property name="M_PI" value="3.1415926535897931" /> <!-- Macro --> <xacro:macro name="xtion_pro_live" params="name parent *origin *calibration_origin"> <!-- base link --> <joint name="${name}_joint" type="fixed"> - <insert_block name="origin" /> + <xacro:insert_block name="origin" /> <parent link="${parent}"/> <child link="${name}_link"/> </joint> @@ -82,7 +82,7 @@ </link> <!-- Xtion IR sensor frame --> <joint name="${name}_ir_optical_frame_joint" type="fixed"> - <insert_block name="calibration_origin" /> <!-- macro argument --> + <xacro:insert_block name="calibration_origin" /> <!-- macro argument --> <parent link="${name}_ir_link"/> <child link="${name}_ir_optical_frame"/> </joint> @@ -117,7 +117,7 @@ </link> <!-- Xtion RGB sensor frame --> <joint name="${name}_rgb_optical_frame_joint" type="fixed"> - <insert_block name="calibration_origin" /> <!-- macro argument --> + <xacro:insert_block name="calibration_origin" /> <!-- macro argument --> <parent link="${name}_rgb_link"/> <child link="${name}_rgb_optical_frame"/> </joint> diff --git a/talos_description/urdf/torso/torso.urdf.xacro b/talos_description/urdf/torso/torso.urdf.xacro index 3fd7239920322206e6285854b72364aea046fce1..b2eeacc86f2412b486948b9f29cb3ef99e299758 100644 --- a/talos_description/urdf/torso/torso.urdf.xacro +++ b/talos_description/urdf/torso/torso.urdf.xacro @@ -127,7 +127,7 @@ rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/> <axis xyz="0 0 1" /> <limit lower="${-75.00000 * deg_to_rad}" upper="${75.00000 * deg_to_rad}" - effort="${talos_max_effort}" velocity="${torso_max_vel}" /> + effort="${torso_max_effort}" velocity="${torso_max_vel}" /> <dynamics friction="1.0" damping="1.0"/> <!-- <safety_controller k_position="20"