update launch files

This commit is contained in:
Ilya Uraev 2025-03-10 14:52:35 +03:00
parent 5883ac354a
commit af64efc0a1
2 changed files with 32 additions and 9 deletions

View file

@ -1,6 +1,7 @@
from launch_ros.actions import Node from launch_ros.actions import Node
from launch import LaunchDescription from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, OpaqueFunction from launch.actions import DeclareLaunchArgument, OpaqueFunction
from ament_index_python.packages import get_package_share_directory
from launch_ros.substitutions import FindPackage, FindPackageShare from launch_ros.substitutions import FindPackage, FindPackageShare
from launch.substitutions import ( from launch.substitutions import (
Command, Command,
@ -8,6 +9,7 @@ from launch.substitutions import (
LaunchConfiguration, LaunchConfiguration,
PathJoinSubstitution, PathJoinSubstitution,
) )
import yaml
from rbs_launch_utils.launch_common import ( from rbs_launch_utils.launch_common import (
get_package_share_directory, get_package_share_directory,
load_yaml, load_yaml,
@ -90,9 +92,9 @@ def launch_setup(context, *args, **kwargs):
robot_description_semantic_content = LaunchConfiguration( robot_description_semantic_content = LaunchConfiguration(
"robot_description_semantic" "robot_description_semantic"
).perform(context) ).perform(context)
robot_description_kinematics_filepath = LaunchConfiguration( # robot_description_kinematics_filepath = LaunchConfiguration(
"robot_description_kinematics" # "robot_description_kinematics"
).perform(context) # ).perform(context)
namespace = LaunchConfiguration("namespace").perform(context) namespace = LaunchConfiguration("namespace").perform(context)
moveit_config_package = LaunchConfiguration("moveit_config_package").perform( moveit_config_package = LaunchConfiguration("moveit_config_package").perform(
context context
@ -102,11 +104,11 @@ def launch_setup(context, *args, **kwargs):
robot_description_semantic = { robot_description_semantic = {
"robot_description_semantic": robot_description_semantic_content "robot_description_semantic": robot_description_semantic_content
} }
robot_description_kinematics = { # robot_description_kinematics = {
"robot_description_kinematics": load_yaml_abs( # "robot_description_kinematics": load_yaml_abs(
robot_description_kinematics_filepath # robot_description_kinematics_filepath
) # )
} # }
use_sim_time = {"use_sim_time": use_sim_time} use_sim_time = {"use_sim_time": use_sim_time}
# Planning Configuration # Planning Configuration
@ -133,6 +135,7 @@ def launch_setup(context, *args, **kwargs):
# "moveit_simple_controller_manager/MoveItSimpleControllerManager", # "moveit_simple_controller_manager/MoveItSimpleControllerManager",
# } # }
xacro_mappings = yaml.safe_load(os.path.join(get_package_share_directory("rbs_mill_assist"), "urdf", "xacro_args.yaml"))
moveit_config = ( moveit_config = (
MoveItConfigsBuilder(robot_name="rbs_arm", package_name="rbs_mill_assist") MoveItConfigsBuilder(robot_name="rbs_arm", package_name="rbs_mill_assist")
.robot_description(file_path="urdf/rbs_arm.xacro") .robot_description(file_path="urdf/rbs_arm.xacro")
@ -142,6 +145,7 @@ def launch_setup(context, *args, **kwargs):
.robot_description_kinematics("moveit/kinematics.yaml") .robot_description_kinematics("moveit/kinematics.yaml")
.robot_description_semantic("srdf/rbs_arm.srdf") .robot_description_semantic("srdf/rbs_arm.srdf")
.moveit_cpp("moveit/moveit_cpp.yaml") .moveit_cpp("moveit/moveit_cpp.yaml")
.planning_pipelines(pipelines=["ompl", "chomp"], default_planning_pipeline="chomp")
.planning_scene_monitor( .planning_scene_monitor(
publish_geometry_updates=True, publish_geometry_updates=True,
publish_planning_scene=True, publish_planning_scene=True,
@ -180,7 +184,7 @@ def launch_setup(context, *args, **kwargs):
parameters=[ parameters=[
robot_description, robot_description,
robot_description_semantic, robot_description_semantic,
robot_description_kinematics, # robot_description_kinematics,
ompl_planning_pipeline_config, ompl_planning_pipeline_config,
# trajectory_execution, # trajectory_execution,
moveit_controllers, moveit_controllers,
@ -188,6 +192,14 @@ def launch_setup(context, *args, **kwargs):
use_sim_time, use_sim_time,
robot_description_planning, robot_description_planning,
# moveit_config.to_dict() # moveit_config.to_dict()
# moveit_config.robot_description,
# moveit_config.robot_description_semantic,
# moveit_config.planning_pipelines,
# moveit_config.planning_scene_monitor,
moveit_config.robot_description_kinematics,
# moveit_config.joint_limits,
# moveit_config.trajectory_execution,
], ],
) )
planning_scene_publisher = Node( planning_scene_publisher = Node(

View file

@ -186,6 +186,16 @@ def launch_setup(context, *args, **kwargs):
] ]
) )
publish_ee_pose = Node(
package="rbs_mill_assist",
executable="publish_ee_pose_node",
parameters=[
{"use_sim_time": use_sim_time},
{"base_link": base_link_name},
{"ee_link": ee_link_name}
]
)
nodes_to_start = [ nodes_to_start = [
rbs_robot_setup, rbs_robot_setup,
# rviz_node, # rviz_node,
@ -194,6 +204,7 @@ def launch_setup(context, *args, **kwargs):
gz_bridge, gz_bridge,
grasping_service, grasping_service,
get_named_pose_service, get_named_pose_service,
# publish_ee_pose
# get_workspace # get_workspace
] ]
return nodes_to_start return nodes_to_start