Skip to content

Commit ac36ce6

Browse files
committed
Update motion planning API tutorial
1 parent 7705dd9 commit ac36ce6

File tree

1 file changed

+22
-10
lines changed

1 file changed

+22
-10
lines changed

doc/examples/motion_planning_api/src/motion_planning_api_tutorial.cpp

Lines changed: 22 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -99,8 +99,8 @@ 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("ompl.planning_plugin", planner_plugin_names))
103-
RCLCPP_FATAL(LOGGER, "Could not find planner plugin name");
102+
if (!motion_planning_api_tutorial_node->get_parameter("ompl.planning_plugins", planner_plugin_names))
103+
RCLCPP_FATAL(LOGGER, "Could not find planner plugin names");
104104
try
105105
{
106106
planner_plugin_loader.reset(new pluginlib::ClassLoader<planning_interface::PlannerManager>(
@@ -166,14 +166,14 @@ int main(int argc, char** argv)
166166
geometry_msgs::msg::PoseStamped pose;
167167
pose.header.frame_id = "panda_link0";
168168
pose.pose.position.x = 0.3;
169-
pose.pose.position.y = 0.4;
169+
pose.pose.position.y = 0.0;
170170
pose.pose.position.z = 0.75;
171-
pose.pose.orientation.w = 1.0;
171+
pose.pose.orientation.z = 1.0;
172172

173-
// A tolerance of 0.01 m is specified in position
174-
// and 0.01 radians in orientation
175-
std::vector<double> tolerance_pose(3, 0.01);
176-
std::vector<double> tolerance_angle(3, 0.01);
173+
// A tolerance of 0.1 m is specified in position
174+
// and 0.1 radians in orientation
175+
std::vector<double> tolerance_pose(3, 0.1);
176+
std::vector<double> tolerance_angle(3, 0.1);
177177

178178
// We will create the request as a constraint using a helper function available
179179
// from the
@@ -185,16 +185,28 @@ int main(int argc, char** argv)
185185
req.group_name = PLANNING_GROUP;
186186
req.goal_constraints.push_back(pose_goal);
187187

188+
// Define workspace bounds
189+
req.workspace_parameters.min_corner.x = req.workspace_parameters.min_corner.y =
190+
req.workspace_parameters.min_corner.z = -5.0;
191+
req.workspace_parameters.max_corner.x = req.workspace_parameters.max_corner.y =
192+
req.workspace_parameters.max_corner.z = 5.0;
193+
188194
// We now construct a planning context that encapsulate the scene,
189195
// the request and the response. We call the planner using this
190196
// planning context
191197
planning_interface::PlanningContextPtr context =
192198
planner_instance->getPlanningContext(planning_scene, req, res.error_code);
199+
200+
if (!context)
201+
{
202+
RCLCPP_ERROR(LOGGER, "Failed to create planning context");
203+
return -1;
204+
}
193205
context->solve(res);
194206
if (res.error_code.val != res.error_code.SUCCESS)
195207
{
196208
RCLCPP_ERROR(LOGGER, "Could not compute plan successfully");
197-
return 0;
209+
return -1;
198210
}
199211

200212
// Visualize the result
@@ -246,7 +258,7 @@ int main(int argc, char** argv)
246258
if (res.error_code.val != res.error_code.SUCCESS)
247259
{
248260
RCLCPP_ERROR(LOGGER, "Could not compute plan successfully");
249-
return 0;
261+
return -1;
250262
}
251263
/* Visualize the trajectory */
252264
res.getMessage(response);

0 commit comments

Comments
 (0)