Skip to content

Commit 3dd4948

Browse files
authored
Adding Robotiq gripper to ur10 arm (#105)
* Switched base_link and base_footprint to follow Nav2 convention * Added launch argument to include docking adapter(True for MPO-700 only) * Updated mp_500 and mp_400 urdf * Updated the odometry_frame param in planar move controller * Attatched Robotiq 2f 140 gripper to the arm and created the necessary launch file to visualize the robot and control the joints using joint state publisher gui
1 parent bd5a566 commit 3dd4948

19 files changed

+590
-66
lines changed

Diff for: CMakeLists.txt

+1
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,7 @@ install(DIRECTORY launch
88
maps
99
worlds
1010
robots
11+
rviz
1112
components
1213
models
1314
DESTINATION share/${PROJECT_NAME})

Diff for: components/arm/robotiq_gripper.urdf.xacro

+21
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,21 @@
1+
<?xml version="1.0"?>
2+
<!-- This is the URDF file for Robotiq 2f 140 Gripper-->
3+
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="robotiq_gripper">
4+
5+
<!-- ur_adapter for gripper-->
6+
<xacro:include filename="$(find robotiq_description)/urdf/ur_to_robotiq_adapter.urdf.xacro"/>
7+
<xacro:ur_to_robotiq
8+
prefix=""
9+
parent="$(arg tf_prefix)tool0"
10+
child="neo_gripper_mount_link"
11+
rotation="${pi/2}"
12+
/>
13+
14+
<!-- add gripper-->
15+
<xacro:include filename="$(find robotiq_description)/urdf/robotiq_2f_140_macro.urdf.xacro"/>
16+
<xacro:robotiq_gripper name="robotiq_gripper" prefix="" parent="neo_gripper_mount_link" include_ros2_control="true" sim_ignition="true">
17+
<origin xyz="0 0 0" rpy="0 0 -${pi / 2}"/>
18+
</xacro:robotiq_gripper>
19+
20+
</robot>
21+

Diff for: components/arm/ur_arm.urdf.xacro

+3
Original file line numberDiff line numberDiff line change
@@ -57,5 +57,8 @@
5757
</gazebo>
5858
</xacro:if>
5959

60+
<!-- include robotiq gripper-->
61+
<xacro:include filename="$(find neo_simulation2)/components/arm/robotiq_gripper.urdf.xacro"/>
62+
6063
</robot>
6164

Diff for: components/common_macro/gazebo_object_controller_macro.xacro

+2-2
Original file line numberDiff line numberDiff line change
@@ -28,8 +28,8 @@
2828
<publish_odom_tf>true</publish_odom_tf>
2929

3030
<!-- Frame IDs -->
31-
<odometryFrame>${odom_frame}</odometryFrame>
32-
<robotBaseFrame>${base_frame}</robotBaseFrame>
31+
<odometry_frame>${odom_frame}</odometry_frame>
32+
<robot_base_frame>${base_frame}</robot_base_frame>
3333

3434
<!-- Set odom covariance -->
3535
<covariance_x>0.0001</covariance_x>

Diff for: launch/robot_description.launch.py

+138
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,138 @@
1+
import launch
2+
from ament_index_python.packages import get_package_share_directory
3+
from launch import LaunchDescription
4+
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, OpaqueFunction, RegisterEventHandler
5+
from launch.launch_description_sources import PythonLaunchDescriptionSource
6+
from launch.substitutions import ThisLaunchFileDir, LaunchConfiguration, PythonExpression
7+
from launch_ros.actions import Node
8+
from launch.conditions import IfCondition, UnlessCondition
9+
from launch.event_handlers import OnProcessStart
10+
from launch.actions import TimerAction
11+
import os
12+
from pathlib import Path
13+
import xacro
14+
"""
15+
This code is used for debugging, quick testing, and visualization of the robot with arm and gripper in Rviz.
16+
"""
17+
18+
# OpaqueFunction is used to perform setup actions during launch through a Python function
19+
def launch_setup(context, use_sim_time_arg, use_joint_state_publisher_gui_arg, my_neo_robot_arg, robot_arm_arg):
20+
# Create a list to hold all the nodes
21+
launch_actions = []
22+
23+
robot_description_pkg = get_package_share_directory('neo_simulation2')
24+
25+
use_sim_time = use_sim_time_arg.perform(context).lower() == 'true'
26+
my_neo_robot = my_neo_robot_arg.perform(context)
27+
arm_type = robot_arm_arg.perform(context)
28+
29+
# IfCondition only accepts "True" or "False"
30+
use_joint_state_publisher_gui = str(use_joint_state_publisher_gui_arg.perform(context).lower() == 'true')
31+
32+
# Getting the robot description xacro
33+
robot_description_xacro = os.path.join(
34+
get_package_share_directory('neo_simulation2'),
35+
'robots/'+my_neo_robot+'/',
36+
my_neo_robot+'.urdf.xacro')
37+
38+
# use_gazebo is set to True since this code launches the robot in simulation
39+
xacro_args = {
40+
'use_gazebo': 'false',
41+
'arm_type': arm_type,
42+
'use_docking_adapter': 'false'
43+
}
44+
45+
# Use xacro to process the file with the argunments above
46+
robot_description_file = xacro.process_file(
47+
robot_description_xacro,
48+
mappings=xacro_args
49+
).toxml()
50+
51+
rviz_config = os.path.join(robot_description_pkg, 'rviz', 'robot_description_rviz.rviz')
52+
53+
# Start the joint state publisher gui only if use_joint_state_publisher_gui is True
54+
start_joint_state_publisher_gui_cmd = Node(
55+
package='joint_state_publisher_gui',
56+
executable='joint_state_publisher_gui',
57+
condition=IfCondition(use_joint_state_publisher_gui),
58+
name='joint_state_publisher_gui',
59+
output='screen',
60+
parameters=[{'use_sim_time': use_sim_time}],
61+
)
62+
63+
start_joint_state_publisher_cmd = Node(
64+
package='joint_state_publisher',
65+
executable='joint_state_publisher',
66+
condition=IfCondition(PythonExpression(['not ', use_joint_state_publisher_gui])),
67+
name='joint_state_publisher',
68+
output='screen',
69+
parameters=[{'use_sim_time': use_sim_time}],
70+
)
71+
72+
start_robot_state_publisher_cmd = Node(
73+
package='robot_state_publisher',
74+
executable='robot_state_publisher',
75+
name='robot_state_publisher',
76+
output='screen',
77+
parameters=[{'robot_description':robot_description_file, 'use_sim_time': use_sim_time}],
78+
)
79+
80+
# Rviz node
81+
start_rviz_cmd = Node(
82+
package='rviz2',
83+
namespace='',
84+
executable='rviz2',
85+
name='rviz2',
86+
arguments=['-d' + rviz_config]
87+
)
88+
89+
launch_actions.append(start_rviz_cmd)
90+
launch_actions.append(start_robot_state_publisher_cmd)
91+
launch_actions.append(start_joint_state_publisher_cmd)
92+
launch_actions.append(start_joint_state_publisher_gui_cmd)
93+
94+
return launch_actions
95+
96+
def generate_launch_description():
97+
ld = LaunchDescription()
98+
99+
# Declare launch arguments with default values and descriptions
100+
declare_use_sim_time_arg = DeclareLaunchArgument(
101+
'use_sim_time', default_value='False',
102+
description='Use simulation clock if True (True/False)'
103+
)
104+
declare_use_joint_state_publisher_gui_arg = DeclareLaunchArgument(
105+
'use_joint_state_publisher_gui', default_value='True',
106+
description='Use joint state publisher gui if True (True/False)'
107+
)
108+
declare_my_robot_arg = DeclareLaunchArgument(
109+
'my_robot',
110+
default_value='mpo_700',
111+
description='Robot Types: "mpo_700", "mpo_500", "mp_400", "mp_500"'
112+
)
113+
declare_arm_type_cmd = DeclareLaunchArgument(
114+
'arm_type', default_value='',
115+
description='Arm Types:\n'
116+
'\t Elite Arms: ec66, cs66\n'
117+
'\t Universal Robotics: ur5, ur10, ur5e, ur10e'
118+
)
119+
120+
use_sim_time_arg = LaunchConfiguration('use_sim_time')
121+
use_joint_state_publisher_gui_arg = LaunchConfiguration('use_joint_state_publisher_gui')
122+
robot_arm_arg = LaunchConfiguration('arm_type')
123+
my_neo_robot_arg = LaunchConfiguration('my_robot')
124+
125+
ld.add_action(declare_use_sim_time_arg)
126+
ld.add_action(declare_use_joint_state_publisher_gui_arg)
127+
ld.add_action(declare_my_robot_arg)
128+
ld.add_action(declare_arm_type_cmd)
129+
130+
context_arguments = [use_sim_time_arg, use_joint_state_publisher_gui_arg, my_neo_robot_arg, robot_arm_arg]
131+
opq_func = OpaqueFunction(
132+
function = launch_setup,
133+
args = context_arguments
134+
)
135+
136+
ld.add_action(opq_func)
137+
138+
return ld

Diff for: launch/simulation.launch.py

+21-13
Original file line numberDiff line numberDiff line change
@@ -34,13 +34,14 @@
3434
"""
3535

3636
# OpaqueFunction is used to perform setup actions during launch through a Python function
37-
def launch_setup(context: LaunchContext, my_neo_robot_arg, my_neo_env_arg, robot_arm_arg):
37+
def launch_setup(context: LaunchContext, my_neo_robot_arg, my_neo_env_arg, robot_arm_arg, docking_adapter_arg):
3838
# Create a list to hold all the nodes
3939
launch_actions = []
4040
# The perform method of a LaunchConfiguration is called to evaluate its value.
4141
my_neo_robot = my_neo_robot_arg.perform(context)
4242
my_neo_environment = my_neo_env_arg.perform(context)
4343
robot_arm_type = robot_arm_arg.perform(context)
44+
use_docking_adapter = docking_adapter_arg.perform(context)
4445
use_sim_time = True
4546

4647
robots = ["mpo_700", "mp_400", "mp_500", "mpo_500"]
@@ -86,17 +87,16 @@ def launch_setup(context: LaunchContext, my_neo_robot_arg, my_neo_env_arg, robot
8687
'robots/'+my_neo_robot+'/',
8788
my_neo_robot+'.urdf.xacro')
8889

89-
# mpo robots have the option to mount arms
90-
if (my_neo_robot == "mpo_700" or my_neo_robot == "mpo_500"):
91-
# use_gazebo is set to True since this code launches the robot in simulation
92-
xacro_args = {
93-
'use_gazebo': 'true',
94-
'arm_type': robot_arm_type,
95-
}
96-
else:
97-
xacro_args = {
98-
'use_gazebo': 'true',
99-
}
90+
# Docking adapter is only for MPO 700
91+
if (my_neo_robot != "mpo_700"):
92+
use_docking_adapter = False
93+
94+
# use_gazebo is set to True since this code launches the robot in simulation
95+
xacro_args = {
96+
'use_gazebo': 'true',
97+
'arm_type': robot_arm_type,
98+
'use_docking_adapter': use_docking_adapter
99+
}
100100

101101
# Use xacro to process the file with the argunments above
102102
robot_description_file = xacro.process_file(
@@ -188,16 +188,24 @@ def generate_launch_description():
188188
'\t Universal Robotics: ur5, ur10, ur5e, ur10e'
189189
)
190190

191+
declare_docking_adapter_cmd = DeclareLaunchArgument(
192+
'use_docking_adapter', default_value='False',
193+
description='Set True to use the docking adapter for the robot\n'
194+
'\t Neobotix: docking_adapter'
195+
)
196+
191197
# Create launch configuration variables for the robot and map name
192198
my_neo_robot_arg = LaunchConfiguration('my_robot')
193199
my_neo_env_arg = LaunchConfiguration('world')
194200
robot_arm_arg = LaunchConfiguration('arm_type')
201+
docking_adapter_arg = LaunchConfiguration('use_docking_adapter')
195202

196203
ld.add_action(declare_my_robot_arg)
197204
ld.add_action(declare_world_name_arg)
198205
ld.add_action(declare_arm_type_cmd)
206+
ld.add_action(declare_docking_adapter_cmd)
199207

200-
context_arguments = [my_neo_robot_arg, my_neo_env_arg, robot_arm_arg]
208+
context_arguments = [my_neo_robot_arg, my_neo_env_arg, robot_arm_arg, docking_adapter_arg]
201209

202210
opq_function = OpaqueFunction(
203211
function=launch_setup,
-18.1 KB
Binary file not shown.

Diff for: models/neobotix_ground_plane/model.sdf

+1-1
Original file line numberDiff line numberDiff line change
@@ -37,4 +37,4 @@
3737
</visual>
3838
</link>
3939
</model>
40-
</sdf>
40+
</sdf>

Diff for: models/neobotix_wall_stickers/model.sdf

+1-1
Original file line numberDiff line numberDiff line change
@@ -37,4 +37,4 @@
3737
</visual>
3838
</link>
3939
</model>
40-
</sdf>
40+
</sdf>

Diff for: package.xml

+5-4
Original file line numberDiff line numberDiff line change
@@ -13,11 +13,12 @@
1313
<exec_depend>slam_toolbox</exec_depend>
1414
<exec_depend>neo_nav2_bringup</exec_depend>
1515
<exec_depend>gazebo_ros</exec_depend>
16-
<exec_depend>ur_simulation_gazebo</exec_depend>
1716
<exec_depend>ur_description</exec_depend>
18-
<exec_depend>neo_ur_moveit_config</exec_depend>
19-
<exec_depend>elite_description</exec_depend>
20-
<exec_depend>elite_gazebo</exec_depend>
17+
<exec_depend>controller_manager</exec_depend>
18+
<exec_depend>gazebo_ros2_control</exec_depend>
19+
<exec_depend>ros2_control</exec_depend>
20+
<exec_depend>ros2_controllers</exec_depend>
21+
<exec_depend>robotiq_description</exec_depend>
2122

2223
<test_depend>ament_copyright</test_depend>
2324
<test_depend>ament_flake8</test_depend>

Diff for: robots/mp_400/urdf/mp_400_body.urdf.xacro

+9-9
Original file line numberDiff line numberDiff line change
@@ -3,15 +3,6 @@
33

44
<link name="base_footprint"/>
55

6-
<joint name="base_footprint_joint" type="fixed">
7-
<origin rpy="0 0 0" xyz="0 0 0"/>
8-
<axis xyz="0 0 -1"/>
9-
<!-- <limit effort="1000.0" lower="-1e+16" upper="1e+16" velocity="3.5"/> -->
10-
<joint_properties damping="1" friction="1"/>
11-
<parent link="base_footprint"/>
12-
<child link="base_link"/>
13-
</joint>
14-
156
<link name="base_link">
167
<inertial>
178
<mass value="30"/>
@@ -32,6 +23,15 @@
3223
</collision>
3324
</link>
3425

26+
<joint name="base_footprint_joint" type="fixed">
27+
<origin rpy="0 0 0" xyz="0 0 0"/>
28+
<axis xyz="0 0 -1"/>
29+
<!-- <limit effort="1000.0" lower="-1e+16" upper="1e+16" velocity="3.5"/> -->
30+
<joint_properties damping="1" friction="1"/>
31+
<parent link="base_link"/>
32+
<child link="base_footprint"/>
33+
</joint>
34+
3535
<!-- Sensors -->
3636
<joint name="lidar_1_joint" type="fixed">
3737
<axis xyz="0 1 0"/>

Diff for: robots/mp_400/urdf/mp_400_gazebo.urdf.xacro

+1-1
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,7 @@
3030
command_topic="cmd_vel"
3131
odometry_topic="odom"
3232
odom_frame="odom"
33-
base_frame="base_footprint"
33+
base_frame="base_link"
3434
max_wheel_torque="1000"
3535
max_acceleration="20.0"
3636
/>

Diff for: robots/mp_500/urdf/mp_500_body.urdf.xacro

+9-9
Original file line numberDiff line numberDiff line change
@@ -3,15 +3,6 @@
33

44
<link name="base_footprint"/>
55

6-
<joint name="base_footprint_joint" type="fixed">
7-
<origin rpy="0 0 0" xyz="0 0 0"/>
8-
<axis xyz="0 0 -1"/>
9-
<!-- <limit effort="1000.0" lower="-1e+16" upper="1e+16" velocity="3.5"/> -->
10-
<joint_properties damping="1" friction="1"/>
11-
<parent link="base_footprint"/>
12-
<child link="base_link"/>
13-
</joint>
14-
156
<link name="base_link">
167
<inertial>
178
<mass value="5"/>
@@ -32,6 +23,15 @@
3223
</collision>
3324
</link>
3425

26+
<joint name="base_footprint_joint" type="fixed">
27+
<origin rpy="0 0 0" xyz="0 0 0"/>
28+
<axis xyz="0 0 -1"/>
29+
<!-- <limit effort="1000.0" lower="-1e+16" upper="1e+16" velocity="3.5"/> -->
30+
<joint_properties damping="1" friction="1"/>
31+
<parent link="base_link"/>
32+
<child link="base_footprint"/>
33+
</joint>
34+
3535
<joint name="caster_wheel_joint" type="fixed">
3636
<origin rpy="-1.570796 0 1.570796 " xyz="-0.43 0. 0.176"/>
3737
<axis xyz="0 -1 0"/>

Diff for: robots/mp_500/urdf/mp_500_gazebo.urdf.xacro

+1-1
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,7 @@
1919
command_topic="cmd_vel"
2020
odometry_topic="odom"
2121
odom_frame="odom"
22-
base_frame="base_footprint"
22+
base_frame="base_link"
2323
max_wheel_torque="200"
2424
max_acceleration="1.0"
2525
/>

0 commit comments

Comments
 (0)