2021-10-19 20:52:07 +04:00
import os
import yaml
from launch import LaunchDescription
from launch . actions import DeclareLaunchArgument , OpaqueFunction
from launch . substitutions import LaunchConfiguration , PathJoinSubstitution
from launch_ros . actions import Node
from launch_ros . substitutions import FindPackageShare
from ament_index_python import get_package_share_directory
def load_yaml ( package_name : str , file_path : str ) :
package_path = get_package_share_directory ( package_name )
absolute_file_path = os . path . join ( package_path , file_path )
try :
with open ( absolute_file_path , " r " ) as f :
return yaml . safe_load ( f )
except EnvironmentError :
return None
def load_file ( package_name : str , file_path : str ) - > str :
package_path = get_package_share_directory ( package_name )
absolut_file_path = os . path . join ( package_path , file_path )
try :
with open ( absolut_file_path , " r " ) as f :
return f . read ( )
except EnvironmentError :
return None
def launch_setup ( context , * args , * * kwargs ) :
# Evaluate frequently used variables
model = LaunchConfiguration ( " model " ) . perform ( context )
# Configure robot_description
robot_description = { " robot_description " : LaunchConfiguration ( " robot_description " ) }
# Robot semantics SRDF
robot_description_semantic = {
2021-10-19 23:26:26 +04:00
" robot_description_semantic " : load_file ( " rasms_moveit_config " , " srdf/ {} .srdf " . format ( model ) )
2021-10-19 20:52:07 +04:00
}
# Kinematics
2021-10-19 23:26:26 +04:00
kinematics_yaml = load_yaml ( " rasms_moveit_config " , " config/kinematics.yml " )
2021-10-19 20:52:07 +04:00
# Update group name
kinematics_yaml [ " {} _arm " . format ( model ) ] = kinematics_yaml [ " group_name " ]
del kinematics_yaml [ " group_name " ]
# Joint limits
robot_description_planning = {
" robot_description_planning " : PathJoinSubstitution (
[
2021-10-19 23:26:26 +04:00
FindPackageShare ( " rasms_moveit_config " ) ,
2021-10-19 20:52:07 +04:00
" config/joint_limits.yml "
]
)
}
# Planning
2021-11-03 15:18:12 +04:00
#ompl_yaml = load_yaml("rasms_moveit_config", "config/ompl_planning.yml")
2021-10-19 20:52:07 +04:00
planning = {
" move_group " : {
" planning_plugin " : " ompl_interface/OMPLPlanner " ,
" request_adapters " : " default_planner_request_adapters/AddTimeParameterization default_planner_request_adapters/FixWorkspaceBounds default_planner_request_adapters/FixStartStateBounds default_planner_request_adapters/FixStartStateCollision default_planner_request_adapters/FixStartStatePathConstraints " ,
" start_state_max_bounds_error " : 0.1
}
}
# Trajectory execution
trajectory_execution = { " allow_trajectory_execution " : True ,
" moveit_manage_controllers " : True }
# Controllers
2021-11-03 15:18:12 +04:00
moveit_simple_controller_yml = load_yaml (
2021-10-19 20:52:07 +04:00
LaunchConfiguration ( " moveit_controller_configurations_package " ) . perform ( context ) ,
LaunchConfiguration ( " moveit_controller_configurations " ) . perform ( context )
)
2021-11-03 15:18:12 +04:00
moveit_controllers = { " moveit_simple_controller_manager " : moveit_simple_controller_yml ,
2021-10-19 20:52:07 +04:00
" moveit_controller_manager " : " moveit_simple_controller_manager/MoveItSimpleControllerManager " }
2021-11-03 15:18:12 +04:00
ompl_planning_pipeline_config = {
" ompl " : {
" planning_plugin " : " ompl_interface/OMPLPlanner " ,
" request_adapters " : """ default_planner_request_adapters/AddTimeOptimalParameterization default_planner_request_adapters/FixWorkspaceBounds default_planner_request_adapters/FixStartStateBounds default_planner_request_adapters/FixStartStateCollision default_planner_request_adapters/FixStartStatePathConstraints """ ,
" start_state_max_bounds_error " : 0.1 ,
}
}
ompl_planning_yml = load_yaml (
" rasms_moveit_config " , " config/ompl_planning.yml "
)
ompl_planning_pipeline_config [ " ompl " ] . update ( ompl_planning_yml )
2021-10-19 20:52:07 +04:00
# Planning scene
planning_scene_monitor_parameters = { " publish_planning_scene " : True ,
" publish_geometry_updates " : True ,
" publish_state_updates " : True ,
" publish_transforms_updates " : True }
2021-11-03 15:18:12 +04:00
moveit_cpp_yaml_file_name = (
get_package_share_directory ( " rasms_moveit_config " ) + " /config/moveit_cpp.yml "
)
2021-10-19 20:52:07 +04:00
# Time configuration
use_sim_time = { " use_sime_time " : LaunchConfiguration ( " sim " ) }
# Prepare move group node
2021-11-07 16:02:53 +04:00
move_group_node = Node (
package = " moveit_ros_move_group " ,
executable = " move_group " ,
output = " screen " ,
arguments = [ " --ros-args " ] ,
parameters = [
robot_description ,
robot_description_semantic ,
kinematics_yaml ,
robot_description_planning ,
ompl_planning_pipeline_config ,
planning ,
trajectory_execution ,
moveit_controllers ,
planning_scene_monitor_parameters ,
use_sim_time
]
)
2021-11-03 15:18:12 +04:00
2021-11-07 16:02:53 +04:00
""" moveit_cpp_node = Node(
2021-11-03 15:18:12 +04:00
name = " moveit_cpp_actions " ,
package = " rasms_moveit_actions " ,
executable = " rasms_moveit " ,
2021-10-19 20:52:07 +04:00
output = " screen " ,
parameters = [
2021-11-03 15:18:12 +04:00
moveit_cpp_yaml_file_name ,
2021-10-19 20:52:07 +04:00
robot_description ,
robot_description_semantic ,
kinematics_yaml ,
2021-11-03 15:18:12 +04:00
ompl_planning_pipeline_config ,
2021-10-19 20:52:07 +04:00
moveit_controllers ,
2021-11-03 15:18:12 +04:00
] ,
2021-11-07 16:02:53 +04:00
) """
2021-10-19 20:52:07 +04:00
2021-11-03 15:18:12 +04:00
""" robot_state_publisher = Node(
2021-10-19 20:52:07 +04:00
package = " robot_state_publisher " ,
executable = " robot_state_publisher " ,
output = " screen " ,
parameters = [ robot_description ]
2021-11-03 15:18:12 +04:00
) """
2021-10-19 20:52:07 +04:00
spawn_controller = Node (
package = " controller_manager " ,
executable = " spawner.py " ,
arguments = [ " joint_state_broadcaster " ] ,
output = " screen " ,
)
# RViz
2021-11-03 15:18:12 +04:00
rviz_config = PathJoinSubstitution ( [ FindPackageShare ( " rasms_moveit_config " ) , " config/rasms.rviz " ] )
2021-10-19 20:52:07 +04:00
rviz = Node (
package = " rviz2 " ,
executable = " rviz2 " ,
parameters = [
robot_description ,
robot_description_semantic ,
2021-11-07 16:02:53 +04:00
use_sim_time ,
kinematics_yaml
2021-10-19 20:52:07 +04:00
] ,
arguments = [
2021-11-07 18:59:07 +04:00
' -d ' , rviz_config
2021-10-19 20:52:07 +04:00
]
)
return [
2021-11-07 16:02:53 +04:00
move_group_node ,
#moveit_cpp_node,
2021-10-19 20:52:07 +04:00
rviz ,
2021-11-03 15:18:12 +04:00
#robot_state_publisher,
2021-10-19 20:52:07 +04:00
spawn_controller
]
def generate_launch_description ( ) :
# Launch arguments
launch_args = [ ]
launch_args . append (
DeclareLaunchArgument (
name = " robot_description " ,
description = " Robot description XML file. "
)
)
launch_args . append (
DeclareLaunchArgument (
name = " model " ,
2021-10-19 23:26:26 +04:00
default_value = " rasms_description " ,
2021-10-19 20:52:07 +04:00
description = " Desired LBR model. Use model:=iiwa7/iiwa14/med7/med14. "
)
)
launch_args . append (
DeclareLaunchArgument (
name = " moveit_controller_configurations_package " ,
2021-10-19 23:26:26 +04:00
default_value = " rasms_moveit_config " ,
2021-10-19 20:52:07 +04:00
description = " Package that contains MoveIt! controller configurations. "
)
)
launch_args . append (
DeclareLaunchArgument (
name = " moveit_controller_configurations " ,
2021-10-19 23:26:26 +04:00
default_value = " config/rasms_moveit_controllers.yml " ,
2021-10-19 20:52:07 +04:00
description = " Relative path to MoveIt! controller configurations YAML file. Note that the joints in the controllers must be named according to the robot_name. "
)
)
launch_args . append ( DeclareLaunchArgument (
name = " sim " ,
default_value = " true " ,
description = " Launch robot in simulation or on real setup. "
) )
return LaunchDescription (
launch_args + [
OpaqueFunction ( function = launch_setup )
] )