Skip to content

Commit f61dfd4

Browse files
committed
TMP
1 parent 52be8f2 commit f61dfd4

File tree

3 files changed

+54
-18
lines changed

3 files changed

+54
-18
lines changed

doc/how_to_guides/planner_cost_functions/config/planner_cost_moveit_cpp.yaml

+3-3
Original file line numberDiff line numberDiff line change
@@ -10,12 +10,12 @@ planning_scene_monitor_options:
1010

1111
# Define which planning pipelines are loaded by moveit_cpp. These loaded pipelines will be available for simple and parallel planning
1212
planning_pipelines:
13-
pipeline_names: ["ompl", "stomp"]
13+
pipeline_names: ["ompl_stomp"]
1414

1515
plan_request_params:
1616
planning_attempts: 1
17-
planning_pipeline: stomp
17+
planning_pipeline: ompl_stomp
1818
planner_id: "stomp"
1919
max_velocity_scaling_factor: 1.0
2020
max_acceleration_scaling_factor: 1.0
21-
planning_time: 5.0
21+
planning_time: 30.0

doc/how_to_guides/planner_cost_functions/launch/planner_cost_functions.launch.py

+27-2
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,6 @@ def launch_setup(context, *args, **kwargs):
4242
.planning_scene_monitor(
4343
publish_robot_description=True, publish_robot_description_semantic=True
4444
)
45-
.planning_pipelines("ompl", ["ompl", "stomp"])
4645
.trajectory_execution(file_path="config/moveit_controllers.yaml")
4746
.moveit_cpp(
4847
os.path.join(
@@ -71,13 +70,39 @@ def launch_setup(context, *args, **kwargs):
7170
},
7271
}
7372

73+
# Load additional OMPL pipeline
74+
ompl_stomp_planning_pipeline_config = {
75+
"ompl_stomp": {
76+
"planning_plugin": "ompl_interface/OMPLPlanner",
77+
"request_adapters": """\
78+
stomp_moveit/StompSmoothingAdapter \
79+
default_planner_request_adapters/AddTimeOptimalParameterization \
80+
default_planner_request_adapters/FixWorkspaceBounds \
81+
default_planner_request_adapters/FixStartStateBounds \
82+
default_planner_request_adapters/FixStartStateCollision \
83+
default_planner_request_adapters/FixStartStatePathConstraints \
84+
""",
85+
"start_state_max_bounds_error": 0.1,
86+
"planner_configs": {
87+
"RRTConnectkConfigDefault": {
88+
"type": "geometric::RRTConnect",
89+
"range": 0.0, # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()}
90+
}
91+
},
92+
}
93+
}
94+
7495
# MoveItCpp demo executable
7596
moveit_cpp_node = Node(
7697
name="planner_cost_functions_example",
7798
package="moveit2_tutorials",
7899
executable="planner_cost_functions_example",
79100
output="screen",
80-
parameters=[moveit_config.to_dict(), warehouse_ros_config],
101+
parameters=[
102+
moveit_config.to_dict(),
103+
ompl_stomp_planning_pipeline_config,
104+
warehouse_ros_config,
105+
],
81106
)
82107

83108
# RViz

doc/how_to_guides/planner_cost_functions/src/planner_cost_functions_main.cpp

+24-13
Original file line numberDiff line numberDiff line change
@@ -297,6 +297,17 @@ class Demo
297297
<< " max_velocity_scaling_factor: " << plan_request_parameters.max_velocity_scaling_factor << ','
298298
<< " max_acceleration_scaling_factor: " << plan_request_parameters.max_acceleration_scaling_factor);
299299

300+
// planning_component_->setStateCostFunction(
301+
// [robot_start_state, group_name, planning_scene](const std::vector<double>& state_vector) mutable {
302+
// // Publish robot state
303+
// // auto const ee_tip = robot_state.getJointModelGroup(PLANNING_GROUP)->getOnlyOneEndEffectorTip();
304+
// // this->getVisualTools().publishSphere(robot_state.getGlobalLinkTransform(ee_tip), rviz_visual_tools::GREEN,
305+
// // rviz_visual_tools::MEDIUM); this->getVisualTools().trigger();
306+
// auto clearance_cost_fn =
307+
// moveit::cost_functions::getClearanceCostFn(*robot_start_state, group_name, planning_scene);
308+
// return clearance_cost_fn(state_vector);
309+
// });
310+
300311
std::vector<planning_interface::MotionPlanResponse> solutions;
301312
solutions.reserve(pipeline_planner_pairs.size());
302313
for (auto const& pipeline_planner_pair : pipeline_planner_pairs)
@@ -310,18 +321,18 @@ class Demo
310321
auto robot_model_ptr = moveit_cpp_->getRobotModel();
311322
auto joint_model_group_ptr = robot_model_ptr->getJointModelGroup(PLANNING_GROUP);
312323
// Check if PlanningComponents succeeded in finding the plan
313-
for (auto const& plan_solution : solutions)
314-
{
315-
if (plan_solution.trajectory)
316-
{
317-
RCLCPP_INFO_STREAM(LOGGER, plan_solution.planner_id.c_str()
318-
<< ": " << colorToString(rviz_visual_tools::Colors(color_index)));
319-
// Visualize the trajectory in Rviz
320-
visual_tools_.publishTrajectoryLine(plan_solution.trajectory, joint_model_group_ptr,
321-
rviz_visual_tools::Colors(color_index));
322-
color_index++;
323-
}
324-
}
324+
// for (auto const& plan_solution : solutions)
325+
//{
326+
// if (plan_solution.trajectory)
327+
// {
328+
// RCLCPP_INFO_STREAM(LOGGER, plan_solution.planner_id.c_str()
329+
// << ": " << colorToString(rviz_visual_tools::Colors(color_index)));
330+
// // Visualize the trajectory in Rviz
331+
// visual_tools_.publishTrajectoryLine(plan_solution.trajectory, joint_model_group_ptr,
332+
// rviz_visual_tools::Colors(color_index));
333+
// color_index++;
334+
// }
335+
//}
325336
visual_tools_.trigger();
326337
}
327338

@@ -367,7 +378,7 @@ int main(int argc, char** argv)
367378
demo.setQueryGoal();
368379

369380
demo.planAndVisualize(
370-
{ { "ompl", "RRTConnectkConfigDefault" }, { "ompl", "RRTstarkConfigDefault" }, { "stomp", "stomp" } });
381+
{ { "ompl_stomp", "RRTConnectkConfigDefault" }, /*{ "ompl", "RRTstarkConfigDefault" }, { "stomp", "stomp" }*/ });
371382

372383
demo.getVisualTools().prompt("Press 'next' in the RvizVisualToolsGui window to finish the demo");
373384
rclcpp::shutdown();

0 commit comments

Comments
 (0)