Skip to content

Commit c9d1469

Browse files
authored
Fix parameters in motion planning API tutorial (#833)
* fix parameters in motion_planning_api_tutorial Signed-off-by: Paul Gesel <[email protected]> * run pre-commit Signed-off-by: Paul Gesel <[email protected]> --------- Signed-off-by: Paul Gesel <[email protected]>
1 parent b2cd6c0 commit c9d1469

File tree

2 files changed

+11
-53
lines changed

2 files changed

+11
-53
lines changed
Lines changed: 10 additions & 52 deletions
Original file line numberDiff line numberDiff line change
@@ -1,68 +1,26 @@
1-
import os
2-
import yaml
31
from launch import LaunchDescription
42
from launch_ros.actions import Node
5-
from ament_index_python.packages import get_package_share_directory
6-
7-
8-
def load_file(package_name, file_path):
9-
package_path = get_package_share_directory(package_name)
10-
absolute_file_path = os.path.join(package_path, file_path)
11-
12-
try:
13-
with open(absolute_file_path, "r") as file:
14-
return file.read()
15-
except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available
16-
return None
17-
18-
19-
def load_yaml(package_name, file_path):
20-
package_path = get_package_share_directory(package_name)
21-
absolute_file_path = os.path.join(package_path, file_path)
22-
23-
try:
24-
with open(absolute_file_path, "r") as file:
25-
return yaml.safe_load(file)
26-
except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available
27-
return None
3+
from moveit_configs_utils import MoveItConfigsBuilder
284

295

306
def generate_launch_description():
31-
robot_description_config = load_file(
32-
"moveit_resources_panda_description", "urdf/panda.urdf"
7+
moveit_config = (
8+
MoveItConfigsBuilder("moveit_resources_panda")
9+
.robot_description(file_path="config/panda.urdf.xacro")
10+
.robot_description_semantic(file_path="config/panda.srdf")
11+
.trajectory_execution(file_path="config/moveit_controllers.yaml")
12+
.planning_pipelines(pipelines=["ompl"])
13+
.to_moveit_configs()
3314
)
34-
robot_description = {"robot_description": robot_description_config}
35-
36-
robot_description_semantic_config = load_file(
37-
"moveit_resources_panda_moveit_config", "config/panda.srdf"
38-
)
39-
robot_description_semantic = {
40-
"robot_description_semantic": robot_description_semantic_config
41-
}
42-
43-
kinematics_yaml = load_yaml(
44-
"moveit_resources_panda_moveit_config", "config/kinematics.yaml"
45-
)
46-
47-
planning_yaml = load_yaml(
48-
"moveit_resources_panda_moveit_config", "config/ompl_planning.yaml"
49-
)
50-
51-
planning_plugin = {"planning_plugin": "ompl_interface/OMPLPlanner"}
5215

5316
return LaunchDescription(
5417
[
5518
Node(
5619
package="moveit2_tutorials",
5720
executable="motion_planning_api_tutorial",
5821
name="motion_planning_api_tutorial",
59-
parameters=[
60-
robot_description,
61-
robot_description_semantic,
62-
kinematics_yaml,
63-
planning_yaml,
64-
planning_plugin,
65-
],
22+
output="screen",
23+
parameters=[moveit_config.to_dict()],
6624
)
6725
]
6826
)

doc/examples/motion_planning_api/src/motion_planning_api_tutorial.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -99,7 +99,7 @@ int main(int argc, char** argv)
9999
// We will get the name of planning plugin we want to load
100100
// from the ROS parameter server, and then load the planner
101101
// making sure to catch all exceptions.
102-
if (!motion_planning_api_tutorial_node->get_parameter("planning_plugin", planner_plugin_name))
102+
if (!motion_planning_api_tutorial_node->get_parameter("ompl.planning_plugin", planner_plugin_name))
103103
RCLCPP_FATAL(LOGGER, "Could not find planner plugin name");
104104
try
105105
{

0 commit comments

Comments
 (0)