SMACC2
Functions
sm_test_moveit_ur5e_fake_hardware_sim Namespace Reference

Functions

def construct_angle_radians (loader, node)
 
def construct_angle_degrees (loader, node)
 
def load_yaml (package_name, file_path)
 
def launch_setup (context, *args, **kwargs)
 
def generate_launch_description ()
 

Function Documentation

◆ construct_angle_degrees()

def sm_test_moveit_ur5e_fake_hardware_sim.construct_angle_degrees (   loader,
  node 
)
utility function for converting degrees into radians from yaml.

Definition at line 42 of file sm_test_moveit_ur5e_fake_hardware_sim.launch.py.

42def construct_angle_degrees(loader, node):
43 """utility function for converting degrees into radians from yaml."""
44 return math.radians(construct_angle_radians(loader, node))
45
46

References construct_angle_radians().

Here is the call graph for this function:

◆ construct_angle_radians()

def sm_test_moveit_ur5e_fake_hardware_sim.construct_angle_radians (   loader,
  node 
)
utility function to construct radian values from yaml.

Definition at line 33 of file sm_test_moveit_ur5e_fake_hardware_sim.launch.py.

33def construct_angle_radians(loader, node):
34 """utility function to construct radian values from yaml."""
35 value = loader.construct_scalar(node)
36 try:
37 return float(value)
38 except SyntaxError:
39 raise Exception("invalid expression: %s" % value)
40
41

Referenced by construct_angle_degrees().

Here is the caller graph for this function:

◆ generate_launch_description()

def sm_test_moveit_ur5e_fake_hardware_sim.generate_launch_description ( )

Definition at line 191 of file sm_test_moveit_ur5e_fake_hardware_sim.launch.py.

192 declared_arguments = []
193 # General arguments
194 declared_arguments.append(
195 DeclareLaunchArgument(
196 "runtime_config_package",
197 default_value="ur_bringup",
198 description='Package with the controller\'s configuration in "config" folder. \
199 Usually the argument is not set, it enables use of a custom setup.',
200 )
201 )
202 declared_arguments.append(
203 DeclareLaunchArgument(
204 "controllers_file",
205 default_value="ur_controllers.yaml",
206 description="YAML file with the controllers configuration.",
207 )
208 )
209 declared_arguments.append(
210 DeclareLaunchArgument(
211 "description_package",
212 default_value="ur_description",
213 description="Description package with robot URDF/XACRO files. Usually the argument \
214 is not set, it enables use of a custom description.",
215 )
216 )
217 declared_arguments.append(
218 DeclareLaunchArgument(
219 "description_file",
220 default_value="ur.urdf.xacro",
221 description="URDF/XACRO description file with the robot.",
222 )
223 )
224 declared_arguments.append(
225 DeclareLaunchArgument(
226 "moveit_config_package",
227 default_value="ur_moveit_config",
228 description="MoveIt config package with robot SRDF/XACRO files. Usually the argument \
229 is not set, it enables use of a custom moveit config.",
230 )
231 )
232 declared_arguments.append(
233 DeclareLaunchArgument(
234 "moveit_config_file",
235 default_value="ur.srdf.xacro",
236 description="MoveIt SRDF/XACRO description file with the robot.",
237 )
238 )
239 declared_arguments.append(
240 DeclareLaunchArgument(
241 "prefix",
242 default_value='""',
243 description="Prefix of the joint names, useful for \
244 multi-robot setup. If changed than also joint names in the controllers' configuration \
245 have to be updated.",
246 )
247 )
248 declared_arguments.append(
249 DeclareLaunchArgument("launch_rviz", default_value="true", description="Launch RViz?")
250 )
251
252 return LaunchDescription(declared_arguments + [OpaqueFunction(function=launch_setup)])

◆ launch_setup()

def sm_test_moveit_ur5e_fake_hardware_sim.launch_setup (   context,
args,
**  kwargs 
)

Definition at line 67 of file sm_test_moveit_ur5e_fake_hardware_sim.launch.py.

67def launch_setup(context, *args, **kwargs):
68
69 ur_type = "ur5e"
70
71 # General arguments
72 runtime_config_package = LaunchConfiguration("runtime_config_package")
73 controllers_file = LaunchConfiguration("controllers_file")
74 description_package = LaunchConfiguration("description_package")
75 description_file = LaunchConfiguration("description_file")
76 moveit_config_package = LaunchConfiguration("moveit_config_package")
77 moveit_config_file = LaunchConfiguration("moveit_config_file")
78 prefix = LaunchConfiguration("prefix")
79
80 robot_description_content = Command(
81 [
82 PathJoinSubstitution([FindExecutable(name="xacro")]),
83 " ",
84 PathJoinSubstitution(
85 [FindPackageShare(description_package), "urdf", description_file]
86 ),
87 " ",
88 "name:=",
89 "ur",
90 " ",
91 "ur_type:=",
92 ur_type,
93 " ",
94 "prefix:=",
95 prefix,
96 " ",
97 ]
98 )
99 robot_description = {"robot_description": robot_description_content}
100
101 # MoveIt Configuration
102 robot_description_semantic_content = Command(
103 [
104 PathJoinSubstitution([FindExecutable(name="xacro")]),
105 " ",
106 PathJoinSubstitution(
107 [FindPackageShare(moveit_config_package), "srdf", moveit_config_file]
108 ),
109 " ",
110 "name:=",
111 "ur",
112 " ",
113 "ur_type:=",
114 ur_type,
115 " ",
116 "prefix:=",
117 prefix,
118 " ",
119 ]
120 )
121 robot_description_semantic = {"robot_description_semantic": robot_description_semantic_content}
122
123 kinematics_yaml = load_yaml("ur_moveit_config", "config/kinematics.yaml")
124 robot_description_kinematics = {"robot_description_kinematics": kinematics_yaml}
125
126 smacc2_sm_config = PathJoinSubstitution(
127 [
128 FindPackageShare("sm_test_moveit_ur5_sim"),
129 "config",
130 "sm_test_moveit_ur5_sim_config.yaml",
131 ]
132 )
133
134 sm_test_moveit_ur5_sim_node = Node(
135 package="sm_test_moveit_ur5_sim",
136 executable="sm_test_moveit_ur5_sim_node",
137 prefix="xterm -xrm 'XTerm*scrollBar: true' -xrm 'xterm*rightScrollBar: true' -hold -sl 10000 -geometry 1000x600 -e",
138 parameters=[
139 robot_description,
140 robot_description_semantic,
141 robot_description_kinematics,
142 smacc2_sm_config,
143 ],
144 arguments=["--log-level", "smacc2:=DEBUG"],
145 )
146
147 ur_control_launch = IncludeLaunchDescription(
148 PythonLaunchDescriptionSource(
149 [FindPackageShare("ur_bringup"), "/launch", "/ur_control.launch.py"]
150 ),
151 launch_arguments={
152 "robot_ip": "xxx.yyy.zzz.www",
153 "ur_type": ur_type,
154 "runtime_config_package": runtime_config_package,
155 "controllers_file": controllers_file,
156 "description_package": description_package,
157 "description_file": description_file,
158 "robot_controller": "scaled_joint_trajectory_controller",
159 "use_fake_hardware": "true",
160 "prefix": prefix,
161 "launch_rviz": "false",
162 "initial_joint_controller": "joint_trajectory_controller", # TODO(destogl): remove this when PR #288 in UR-Driver is merged
163 }.items(),
164 )
165
166 ur_moveit_launch = IncludeLaunchDescription(
167 PythonLaunchDescriptionSource(
168 [FindPackageShare("ur_moveit_config"), "/launch", "/ur_moveit.launch.py"]
169 ),
170 launch_arguments={
171 "ur_type": ur_type,
172 "description_package": description_package,
173 "description_file": description_file,
174 "moveit_config_package": moveit_config_package,
175 "moveit_config_file": moveit_config_file,
176 "use_sim_time": "false",
177 "prefix": prefix,
178 "launch_rviz": "true",
179 }.items(),
180 )
181
182 nodes_to_launch = [
183 ur_control_launch,
184 ur_moveit_launch,
185 sm_test_moveit_ur5_sim_node,
186 ]
187
188 return nodes_to_launch
189
190

References load_yaml().

Here is the call graph for this function:

◆ load_yaml()

def sm_test_moveit_ur5e_fake_hardware_sim.load_yaml (   package_name,
  file_path 
)

Definition at line 47 of file sm_test_moveit_ur5e_fake_hardware_sim.launch.py.

47def load_yaml(package_name, file_path):
48 package_path = get_package_share_directory(package_name)
49 absolute_file_path = os.path.join(package_path, file_path)
50
51 try:
52 yaml.SafeLoader.add_constructor("!radians", construct_angle_radians)
53 yaml.SafeLoader.add_constructor("!degrees", construct_angle_degrees)
54 except Exception:
55 raise Exception("yaml support not available; install python-yaml")
56
57 try:
58 with open(absolute_file_path) as file:
59 return yaml.safe_load(file)
60 except OSError: # parent of IOError, OSError *and* WindowsError where available
61 return None
62
63
64# TODO(destogl): END this should be removed when MoveIt can handle parameters properly
65
66

Referenced by launch_setup().

Here is the caller graph for this function: