Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
37 changes: 24 additions & 13 deletions tiago_pro_bringup/launch/tiago_pro_bringup.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,9 @@


from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.actions import DeclareLaunchArgument, GroupAction
from launch.conditions import IfCondition
from launch.substitutions import LaunchConfiguration

from launch_pal.include_utils import include_scoped_launch_py_description
from launch_pal.arg_utils import LaunchArgumentsBase
Expand Down Expand Up @@ -50,6 +52,12 @@ class LaunchArguments(LaunchArgumentsBase):
namespace: DeclareLaunchArgument = CommonArgs.namespace
is_public_sim: DeclareLaunchArgument = CommonArgs.is_public_sim
gazebo_version: DeclareLaunchArgument = CommonArgs.gazebo_version
play_motion2: DeclareLaunchArgument = DeclareLaunchArgument(
"play_motion2",
default_value="True",
description="Launch play_motion2",
choices=["True", "False"],
)


def declare_actions(launch_description: LaunchDescription, launch_args: LaunchArguments):
Expand All @@ -74,18 +82,21 @@ def declare_actions(launch_description: LaunchDescription, launch_args: LaunchAr

launch_description.add_action(default_controllers)

play_motion2 = include_scoped_launch_py_description(
pkg_name='tiago_pro_bringup',
paths=['launch', 'tiago_pro_play_motion2.launch.py'],
launch_arguments={"arm_type_right": launch_args.arm_type_right,
"arm_type_left": launch_args.arm_type_left,
"end_effector_right": launch_args.end_effector_right,
"end_effector_left": launch_args.end_effector_left,
"wrist_model_right": launch_args.wrist_model_right,
"wrist_model_left": launch_args.wrist_model_left,
"use_sim_time": launch_args.use_sim_time,
"has_teleop_arms": launch_args.has_teleop_arms
})
play_motion2 = GroupAction(
condition=IfCondition(LaunchConfiguration("play_motion2")),
actions=[include_scoped_launch_py_description(
pkg_name='tiago_pro_bringup',
paths=['launch', 'tiago_pro_play_motion2.launch.py'],
launch_arguments={"arm_type_right": launch_args.arm_type_right,
"arm_type_left": launch_args.arm_type_left,
"end_effector_right": launch_args.end_effector_right,
"end_effector_left": launch_args.end_effector_left,
"wrist_model_right": launch_args.wrist_model_right,
"wrist_model_left": launch_args.wrist_model_left,
"use_sim_time": launch_args.use_sim_time,
"has_teleop_arms": launch_args.has_teleop_arms
})]
)

launch_description.add_action(play_motion2)

Expand Down
4 changes: 2 additions & 2 deletions tiago_pro_description/config/tiago_pro_configuration.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -28,11 +28,11 @@ tool_changer_left:
default_value: 'True'
end_effector_right:
description: 'End effector model right arm'
choices: ['pal-pro-gripper', 'custom', 'no-end-effector', 'allegro-hand']
choices: ['pal-pro-gripper', 'custom', 'no-end-effector', 'allegro-hand', 'pal-atc']
default_value: 'pal-pro-gripper'
end_effector_left:
description: 'End effector model left arm'
choices: ['pal-pro-gripper', 'custom', 'no-end-effector', 'allegro-hand']
choices: ['pal-pro-gripper', 'custom', 'no-end-effector', 'allegro-hand', 'pal-atc']
default_value: 'pal-pro-gripper'
ft_sensor_right:
description: 'FT sensor model right arm'
Expand Down
4 changes: 2 additions & 2 deletions tiago_pro_description/robots/tiago_pro.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -182,10 +182,10 @@
<xacro:if value="${arm_type_teleop_right not in ['tiago-pro-prototype', 'tiago-pro', 'tiago-pro-s', 'no-arm']}">
<xacro:wrong_arm_type_teleop_right />
</xacro:if>
<xacro:if value="${end_effector_left not in ['pal-pro-gripper', 'custom', 'no-end-effector', 'allegro-hand']}">
<xacro:if value="${end_effector_left not in ['pal-pro-gripper', 'custom', 'no-end-effector', 'allegro-hand', 'pal-atc']}">
<xacro:wrong_end_effector_left />
</xacro:if>
<xacro:if value="${end_effector_right not in ['pal-pro-gripper', 'custom', 'no-end-effector', 'allegro-hand']}">
<xacro:if value="${end_effector_right not in ['pal-pro-gripper', 'custom', 'no-end-effector', 'allegro-hand', 'pal-atc']}">
<xacro:wrong_end_effector_right />
</xacro:if>
<xacro:if value="${end_effector_teleop_left not in ['pal-pro-gripper', 'custom', 'no-end-effector', 'allegro-hand']}">
Expand Down
39 changes: 24 additions & 15 deletions tiago_pro_description/ros2_control/ros2_control.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -37,14 +37,14 @@
<xacro:macro name="ros2_control_arms">
<!-- arm left -->
<xacro:if value="${has_arm_left}">
<xacro:ros2_control_arm name="arm_left_1" reduction="121.0" offset_value="${arm_left_1_joint_offset}" use_sea_transmission="${torque_estimation}" />
<xacro:ros2_control_arm name="arm_left_2" reduction="121.0" offset_value="${arm_left_2_joint_offset}" use_sea_transmission="${torque_estimation}" />
<xacro:ros2_control_arm name="arm_left_3" reduction="101.0" offset_value="${arm_left_3_joint_offset}" use_sea_transmission="${torque_estimation}" />
<xacro:ros2_control_arm name="arm_left_4" reduction="101.0" offset_value="${arm_left_4_joint_offset}" use_sea_transmission="${torque_estimation}" />
<xacro:ros2_control_arm name="arm_left_5" reduction="101.0" offset_value="${arm_left_5_joint_offset}" use_sea_transmission="${torque_estimation}" />
<xacro:ros2_control_arm name="arm_left_1" reduction="121.0" offset_value="${arm_left_1_joint_offset}" use_sea_transmission="${torque_estimation}" initial_position="0.5" />
<xacro:ros2_control_arm name="arm_left_2" reduction="121.0" offset_value="${arm_left_2_joint_offset}" use_sea_transmission="${torque_estimation}" initial_position="-1.83" />
<xacro:ros2_control_arm name="arm_left_3" reduction="101.0" offset_value="${arm_left_3_joint_offset}" use_sea_transmission="${torque_estimation}" initial_position="-0.47" />
<xacro:ros2_control_arm name="arm_left_4" reduction="101.0" offset_value="${arm_left_4_joint_offset}" use_sea_transmission="${torque_estimation}" initial_position="-2.35" />
<xacro:ros2_control_arm name="arm_left_5" reduction="101.0" offset_value="${arm_left_5_joint_offset}" use_sea_transmission="${torque_estimation}" initial_position="0.0" />
<xacro:if value="${wrist_model_left != 'short-wrist'}">
<xacro:ros2_control_arm name="arm_left_6" reduction="101.0" offset_value="${arm_left_6_joint_offset}" use_sea_transmission="${torque_estimation}" />
<xacro:ros2_control_arm name="arm_left_7" reduction="101.0" offset_value="${arm_left_7_joint_offset}" use_sea_transmission="${torque_estimation}" />
<xacro:ros2_control_arm name="arm_left_6" reduction="101.0" offset_value="${arm_left_6_joint_offset}" use_sea_transmission="${torque_estimation}" initial_position="-1.2" />
<xacro:ros2_control_arm name="arm_left_7" reduction="101.0" offset_value="${arm_left_7_joint_offset}" use_sea_transmission="${torque_estimation}" initial_position="0.0" />
</xacro:if>
<xacro:if value="${has_ft_sensor_left}">
<xacro:include filename="$(find pal_urdf_utils)/urdf/ft_sensors/ftsensor.ros2_control.xacro"/>
Expand All @@ -54,28 +54,33 @@
<xacro:if value="${end_effector_left == 'pal-pro-gripper'}">
<xacro:ros2_control_pal_pro_gripper name="gripper_left" reduction="1.0" />
</xacro:if>
<xacro:if value="${end_effector_left == 'pal-atc'}">
<xacro:ros2_control_pal_atc name="gripper_left" reduction="1.0" />
</xacro:if>
</xacro:if>

<!-- arm right -->
<xacro:if value="${has_arm_right}">
<xacro:ros2_control_arm name="arm_right_1" reduction="121.0" offset_value="${arm_right_1_joint_offset}" use_sea_transmission="${torque_estimation}" />
<xacro:ros2_control_arm name="arm_right_2" reduction="121.0" offset_value="${arm_right_2_joint_offset}" use_sea_transmission="${torque_estimation}" />
<xacro:ros2_control_arm name="arm_right_3" reduction="101.0" offset_value="${arm_right_3_joint_offset}" use_sea_transmission="${torque_estimation}" />
<xacro:ros2_control_arm name="arm_right_4" reduction="101.0" offset_value="${arm_right_4_joint_offset}" use_sea_transmission="${torque_estimation}" />
<xacro:ros2_control_arm name="arm_right_5" reduction="101.0" offset_value="${arm_right_5_joint_offset}" use_sea_transmission="${torque_estimation}" />
<xacro:ros2_control_arm name="arm_right_1" reduction="121.0" offset_value="${arm_right_1_joint_offset}" use_sea_transmission="${torque_estimation}" initial_position="-0.5" />
<xacro:ros2_control_arm name="arm_right_2" reduction="121.0" offset_value="${arm_right_2_joint_offset}" use_sea_transmission="${torque_estimation}" initial_position="-1.83" />
<xacro:ros2_control_arm name="arm_right_3" reduction="101.0" offset_value="${arm_right_3_joint_offset}" use_sea_transmission="${torque_estimation}" initial_position="0.47" />
<xacro:ros2_control_arm name="arm_right_4" reduction="101.0" offset_value="${arm_right_4_joint_offset}" use_sea_transmission="${torque_estimation}" initial_position="-2.35" />
<xacro:ros2_control_arm name="arm_right_5" reduction="101.0" offset_value="${arm_right_5_joint_offset}" use_sea_transmission="${torque_estimation}" initial_position="0.0" />
<xacro:if value="${wrist_model_right != 'short-wrist'}">
<xacro:ros2_control_arm name="arm_right_6" reduction="101.0" offset_value="${arm_right_6_joint_offset}" use_sea_transmission="${torque_estimation}" />
<xacro:ros2_control_arm name="arm_right_7" reduction="101.0" offset_value="${arm_right_7_joint_offset}" use_sea_transmission="${torque_estimation}" />
<xacro:ros2_control_arm name="arm_right_6" reduction="101.0" offset_value="${arm_right_6_joint_offset}" use_sea_transmission="${torque_estimation}" initial_position="-1.2" />
<xacro:ros2_control_arm name="arm_right_7" reduction="101.0" offset_value="${arm_right_7_joint_offset}" use_sea_transmission="${torque_estimation}" initial_position="0.0" />
</xacro:if>
<xacro:if value="${has_ft_sensor_right}">
<xacro:include filename="$(find pal_urdf_utils)/urdf/ft_sensors/ftsensor.ros2_control.xacro"/>
<xacro:ros2_control_force_torque_sensor name="wrist_right_ft_sensor"/>
</xacro:if>

<xacro:if value="${end_effector_right == 'pal-pro-gripper'}">
<!-- pal-pro-gripper -->
<xacro:ros2_control_pal_pro_gripper name="gripper_right" reduction="1.0" />
</xacro:if>
<xacro:if value="${end_effector_right == 'pal-atc'}">
<xacro:ros2_control_pal_atc name="gripper_right" reduction="1.0" />
</xacro:if>
</xacro:if>

<xacro:if value="${has_teleop_arms}">
Expand Down Expand Up @@ -170,6 +175,10 @@
<xacro:if value="${end_effector_left == 'allegro-hand' or end_effector_right == 'allegro-hand' or end_effector_teleop_left == 'allegro-hand' or end_effector_teleop_right == 'allegro-hand'}">
<xacro:include filename="$(find allegro_hand_description)/urdf/allegro_hand.ros2_control.xacro" />
</xacro:if>

<xacro:if value="${end_effector_left == 'pal-atc' or end_effector_right == 'pal-atc'}">
<xacro:include filename="$(find pal_atc_description)/urdf/gripper.ros2_control.xacro" />
</xacro:if>
<!-- calibration offsets -->
<xacro:include filename="$(arg calibration_offset_dir)/calibration_offset.urdf.xacro" />

Expand Down