add planner configs to planning group in moveit config

This commit is contained in:
Ilya Uraev 2025-03-12 20:49:17 +03:00
parent ed430a825d
commit 1f7dc11289

View file

@ -4,7 +4,7 @@ from launch.actions import DeclareLaunchArgument, OpaqueFunction
from launch.substitutions import (
LaunchConfiguration,
)
from moveit_configs_utils import MoveItConfigsBuilder
from moveit_configs_utils import MoveItConfigsBuilder, moveit_configs_builder
def generate_launch_description():
@ -88,7 +88,6 @@ def launch_setup(context, *args, **kwargs):
}
use_sim_time = {"use_sim_time": use_sim_time}
moveit_config = (
MoveItConfigsBuilder(robot_name="rbs_arm", package_name="rbs_mill_assist")
.trajectory_execution(file_path="moveit/moveit_controllers.yaml")
@ -96,19 +95,31 @@ def launch_setup(context, *args, **kwargs):
.pilz_cartesian_limits("moveit/pilz_cartesian_limits.yaml")
.robot_description_kinematics("moveit/kinematics.yaml")
.robot_description_semantic("srdf/rbs_arm.srdf", mappings={})
.planning_pipelines(pipelines=["ompl", "stomp"], default_planning_pipeline="stomp")
.planning_pipelines(
pipelines=["ompl", "stomp", "chomp"], default_planning_pipeline="ompl"
)
.to_moveit_configs()
)
planners_ids = [
"RRTstar",
"PRM",
"BiTRRT",
"SPARStwo",
]
(
moveit_config.planning_pipelines["ompl"]
.setdefault("arm", {})
# .setdefault("planner_configs", {})
.update(
{"planner_configs":planners_ids}
)
)
move_group_node = Node(
package="moveit_ros_move_group",
executable="move_group",
namespace=namespace,
parameters=[
moveit_config.to_dict(),
robot_description,
use_sim_time
],
parameters=[moveit_config.to_dict(), robot_description, use_sim_time],
)
planning_scene_publisher = Node(
package="rbs_mill_assist",