diff --git a/doc/examples/moveit_cpp/config/moveit_cpp.yaml b/doc/examples/moveit_cpp/config/moveit_cpp.yaml index 8d6915fc56..0dbd6f88ee 100644 --- a/doc/examples/moveit_cpp/config/moveit_cpp.yaml +++ b/doc/examples/moveit_cpp/config/moveit_cpp.yaml @@ -9,11 +9,11 @@ planning_scene_monitor_options: planning_pipelines: #namespace: "moveit_cpp" # optional, default is ~ - pipeline_names: ["stomp"] + pipeline_names: ["ompl"] plan_request_params: planning_attempts: 1 - planning_pipeline: stomp - planner_id: "stomp" + planning_pipeline: ompl + planner_id: "RRTConnectkConfigDefault" max_velocity_scaling_factor: 1.0 max_acceleration_scaling_factor: 1.0 diff --git a/doc/examples/moveit_cpp/launch/moveit_cpp_tutorial.launch.py b/doc/examples/moveit_cpp/launch/moveit_cpp_tutorial.launch.py index 63c2d1d737..4e1a9143c2 100644 --- a/doc/examples/moveit_cpp/launch/moveit_cpp_tutorial.launch.py +++ b/doc/examples/moveit_cpp/launch/moveit_cpp_tutorial.launch.py @@ -11,7 +11,7 @@ def generate_launch_description(): MoveItConfigsBuilder("moveit_resources_panda") .robot_description(file_path="config/panda.urdf.xacro") .trajectory_execution(file_path="config/gripper_moveit_controllers.yaml") - .planning_pipelines("stomp", ["stomp"]) + .planning_pipelines("ompl", ["ompl"]) .moveit_cpp( file_path=get_package_share_directory("moveit2_tutorials") + "/config/moveit_cpp.yaml" diff --git a/doc/how_to_guides/planner_cost_functions/src/planner_cost_functions_main.cpp b/doc/how_to_guides/planner_cost_functions/src/planner_cost_functions_main.cpp index c690be291a..690f9d1472 100644 --- a/doc/how_to_guides/planner_cost_functions/src/planner_cost_functions_main.cpp +++ b/doc/how_to_guides/planner_cost_functions/src/planner_cost_functions_main.cpp @@ -261,12 +261,12 @@ class Demo // Set cost function if (pipeline_config.use_cost_function) { - planning_component_->setStateCostFunction( - [robot_start_state, group_name, planning_scene](const Eigen::VectorXd& state_vector) mutable { - auto clearance_cost_fn = - moveit::cost_functions::createMinJointDisplacementCostFn(*robot_start_state, group_name, planning_scene); - return clearance_cost_fn(state_vector); - }); + planning_component_->setStateCostFunction([robot_start_state, group_name, + planning_scene](const Eigen::VectorXd& state_vector) mutable { + auto clearance_cost_fn = + moveit::cost_functions::createMinJointDisplacementCostFn(*robot_start_state, group_name, planning_scene); + return clearance_cost_fn(state_vector); + }); } else {