Skip to content

Commit 44024e9

Browse files
Merge pull request #194 from clearpathrobotics/rc/humble/1.3
Humble 1.3 Release
2 parents 1299eb7 + dd0df11 commit 44024e9

File tree

3 files changed

+25
-3
lines changed

3 files changed

+25
-3
lines changed

clearpath_generator_common/clearpath_generator_common/description/manipulators.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -71,6 +71,7 @@ def __init__(self, manipulator: BaseManipulator) -> None:
7171
self.NAME: manipulator.name,
7272
self.PARENT: manipulator.parent,
7373
}
74+
self.parameters.update(manipulator.get_urdf_parameters())
7475

7576
@property
7677
def name(self) -> str:
@@ -123,7 +124,6 @@ class UniversalRobotsDescription(ArmDescription):
123124
def __init__(self, arm: BaseArm) -> None:
124125
super().__init__(arm)
125126
self.parameters.pop(self.PORT)
126-
self.parameters.update(arm.get_urdf_parameters())
127127

128128
class FrankaDescription(ArmDescription):
129129
IP = Franka.IP_ADDRESS

clearpath_generator_common/clearpath_generator_common/launch/generator.py

+1
Original file line numberDiff line numberDiff line change
@@ -82,6 +82,7 @@ def __init__(self,
8282
('use_sim_time', 'false'),
8383
('namespace', self.namespace),
8484
('launch_moveit', str(self.clearpath_config.manipulators.moveit.enable).lower()),
85+
('delay_moveit', str(self.clearpath_config.manipulators.moveit.delay))
8586
]
8687
)
8788

clearpath_manipulators/launch/manipulators.launch.py

+23-2
Original file line numberDiff line numberDiff line change
@@ -80,11 +80,25 @@ def generate_launch_description():
8080
description='Launch MoveIt'
8181
)
8282

83+
arg_control_delay = DeclareLaunchArgument(
84+
'control_delay',
85+
default_value='0.0',
86+
description='Control launch delay in seconds.'
87+
)
88+
89+
arg_moveit_delay = DeclareLaunchArgument(
90+
'moveit_delay',
91+
default_value='1.0',
92+
description='MoveIt launch delay in seconds.'
93+
)
94+
8395
# Launch Configurations
8496
setup_path = LaunchConfiguration('setup_path')
8597
use_sim_time = LaunchConfiguration('use_sim_time')
8698
namespace = LaunchConfiguration('namespace')
8799
launch_moveit = LaunchConfiguration('launch_moveit')
100+
control_delay = LaunchConfiguration('control_delay')
101+
moveit_delay = LaunchConfiguration('moveit_delay')
88102

89103
# Launch files
90104
launch_file_manipulators_description = PathJoinSubstitution([
@@ -126,6 +140,11 @@ def generate_launch_description():
126140
]
127141
)
128142

143+
control_delayed = TimerAction(
144+
period=control_delay,
145+
actions=[group_manipulators_action]
146+
)
147+
129148
# Launch MoveIt
130149
moveit_node_action = IncludeLaunchDescription(
131150
PythonLaunchDescriptionSource(launch_file_moveit),
@@ -137,7 +156,7 @@ def generate_launch_description():
137156
)
138157

139158
moveit_delayed = TimerAction(
140-
period=10.0,
159+
period=moveit_delay,
141160
actions=[moveit_node_action]
142161
)
143162

@@ -146,6 +165,8 @@ def generate_launch_description():
146165
ld.add_action(arg_use_sim_time)
147166
ld.add_action(arg_namespace)
148167
ld.add_action(arg_launch_moveit)
149-
ld.add_action(group_manipulators_action)
168+
ld.add_action(arg_control_delay)
169+
ld.add_action(arg_moveit_delay)
170+
ld.add_action(control_delayed)
150171
ld.add_action(moveit_delayed)
151172
return ld

0 commit comments

Comments
 (0)