@@ -99,8 +99,8 @@ int main(int argc, char** argv)
99
99
// We will get the name of planning plugin we want to load
100
100
// from the ROS parameter server, and then load the planner
101
101
// 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 " );
104
104
try
105
105
{
106
106
planner_plugin_loader.reset (new pluginlib::ClassLoader<planning_interface::PlannerManager>(
@@ -166,14 +166,14 @@ int main(int argc, char** argv)
166
166
geometry_msgs::msg::PoseStamped pose;
167
167
pose.header .frame_id = " panda_link0" ;
168
168
pose.pose .position .x = 0.3 ;
169
- pose.pose .position .y = 0.4 ;
169
+ pose.pose .position .y = 0.0 ;
170
170
pose.pose .position .z = 0.75 ;
171
- pose.pose .orientation .w = 1.0 ;
171
+ pose.pose .orientation .z = 1.0 ;
172
172
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 );
177
177
178
178
// We will create the request as a constraint using a helper function available
179
179
// from the
@@ -185,16 +185,28 @@ int main(int argc, char** argv)
185
185
req.group_name = PLANNING_GROUP;
186
186
req.goal_constraints .push_back (pose_goal);
187
187
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
+
188
194
// We now construct a planning context that encapsulate the scene,
189
195
// the request and the response. We call the planner using this
190
196
// planning context
191
197
planning_interface::PlanningContextPtr context =
192
198
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
+ }
193
205
context->solve (res);
194
206
if (res.error_code .val != res.error_code .SUCCESS )
195
207
{
196
208
RCLCPP_ERROR (LOGGER, " Could not compute plan successfully" );
197
- return 0 ;
209
+ return - 1 ;
198
210
}
199
211
200
212
// Visualize the result
@@ -246,7 +258,7 @@ int main(int argc, char** argv)
246
258
if (res.error_code .val != res.error_code .SUCCESS )
247
259
{
248
260
RCLCPP_ERROR (LOGGER, " Could not compute plan successfully" );
249
- return 0 ;
261
+ return - 1 ;
250
262
}
251
263
/* Visualize the trajectory */
252
264
res.getMessage (response);
0 commit comments