|
| 1 | +<?xml version="1.0"?> |
| 2 | + |
| 3 | +<robot xmlns:xacro="http://ros.org/wiki/xacro"> |
| 4 | + |
| 5 | + <xacro:macro name="load_robot" params=" |
| 6 | + parent |
| 7 | + *origin |
| 8 | + prefix |
| 9 | + arm |
| 10 | + gripper |
| 11 | + gripper_joint_name |
| 12 | + dof |
| 13 | + vision |
| 14 | + robot_ip |
| 15 | + username |
| 16 | + password |
| 17 | + port |
| 18 | + port_realtime |
| 19 | + session_inactivity_timeout_ms |
| 20 | + connection_inactivity_timeout_ms |
| 21 | + use_internal_bus_gripper_comm:=false |
| 22 | + use_fake_hardware:=false |
| 23 | + fake_sensor_commands:=false |
| 24 | + sim_gazebo:=false |
| 25 | + sim_ignition:=false |
| 26 | + sim_isaac:=false |
| 27 | + isaac_joint_commands:=/isaac_joint_commands |
| 28 | + isaac_joint_states:=/isaac_joint_states |
| 29 | + use_external_cable:=false |
| 30 | + initial_positions:=${dict(joint_1=0.0,joint_2=0.0,joint_3=0.0,joint_4=0.0,joint_5=0.0,joint_6=0.0,joint_7=0.0)} |
| 31 | + gripper_max_velocity:=100.0 |
| 32 | + gripper_max_force:=100.0 |
| 33 | + gripper_com_port:=/dev/ttyUSB0 |
| 34 | + moveit_active:=false"> |
| 35 | + |
| 36 | + <!-- Include and load arm macro files --> |
| 37 | + <xacro:include filename="$(find kortex_description)/arms/${arm}/${dof}dof/urdf/${arm}_macro.xacro" /> |
| 38 | + |
| 39 | + <!-- Load the arm --> |
| 40 | + <xacro:load_arm |
| 41 | + parent="${parent}" |
| 42 | + dof="${dof}" |
| 43 | + vision="${vision}" |
| 44 | + robot_ip="${robot_ip}" |
| 45 | + username="${username}" |
| 46 | + password="${password}" |
| 47 | + port="${port}" |
| 48 | + port_realtime="${port_realtime}" |
| 49 | + session_inactivity_timeout_ms="${session_inactivity_timeout_ms}" |
| 50 | + connection_inactivity_timeout_ms="${connection_inactivity_timeout_ms}" |
| 51 | + prefix="${prefix}" |
| 52 | + use_internal_bus_gripper_comm="${use_internal_bus_gripper_comm}" |
| 53 | + use_fake_hardware="${use_fake_hardware}" |
| 54 | + fake_sensor_commands="${fake_sensor_commands}" |
| 55 | + sim_gazebo="${sim_gazebo}" |
| 56 | + sim_ignition="${sim_ignition}" |
| 57 | + sim_isaac="${sim_isaac}" |
| 58 | + isaac_joint_commands="${isaac_joint_commands}" |
| 59 | + isaac_joint_states="${isaac_joint_states}" |
| 60 | + gripper_joint_name="${gripper_joint_name}" |
| 61 | + gripper_max_velocity="${gripper_max_velocity}" |
| 62 | + gripper_max_force="${gripper_max_force}" |
| 63 | + use_external_cable="${use_external_cable}" |
| 64 | + initial_positions="${initial_positions}" |
| 65 | + moveit_active="${moveit_active}"> |
| 66 | + <xacro:insert_block name="origin" /> |
| 67 | + </xacro:load_arm> |
| 68 | + |
| 69 | + <!-- If no gripper, define tool frame here --> |
| 70 | + <xacro:if value="${not gripper}"> |
| 71 | + <link name="${prefix}tool_frame"/> |
| 72 | + <joint name="${prefix}tool_frame_joint" type="fixed"> |
| 73 | + <origin xyz="0 0 0" rpy="0 0 0" /> |
| 74 | + <parent link="${prefix}${last_arm_link}" /> |
| 75 | + <child link="${prefix}tool_frame" /> |
| 76 | + <axis xyz="0 0 0" /> |
| 77 | + </joint> |
| 78 | + </xacro:if> |
| 79 | + |
| 80 | + <!-- Include and load the gripper if defined --> |
| 81 | + <xacro:unless value="${not gripper}"> |
| 82 | + <xacro:include filename="$(find kinova_gen3_base_config)/description/robotiq_2f_85_macro.xacro" /> |
| 83 | + <!-- last_arm_link is defined in "$(find kortex_description)/arms/${arm}/urdf/${arm}_macro.xacro" --> |
| 84 | + <xacro:load_gripper |
| 85 | + parent="${prefix}${last_arm_link}" |
| 86 | + prefix="${prefix}" |
| 87 | + use_fake_hardware="${use_fake_hardware}" |
| 88 | + fake_sensor_commands="${fake_sensor_commands}" |
| 89 | + sim_ignition="${sim_ignition}" |
| 90 | + sim_isaac="${sim_isaac}" |
| 91 | + isaac_joint_commands="${isaac_joint_commands}" |
| 92 | + isaac_joint_states="${isaac_joint_states}" |
| 93 | + com_port="${gripper_com_port}" |
| 94 | + use_internal_bus_gripper_comm="${use_internal_bus_gripper_comm}" |
| 95 | + moveit_active="${moveit_active}"/> |
| 96 | + </xacro:unless> |
| 97 | + |
| 98 | + </xacro:macro> |
| 99 | + |
| 100 | +</robot> |
0 commit comments