update, add conditions and fix mistakes
This commit is contained in:
parent
ef563a5dc0
commit
5314c1adf5
3 changed files with 63 additions and 38 deletions
|
@ -163,6 +163,18 @@ def generate_launch_description():
|
|||
declared_arguments.append(
|
||||
DeclareLaunchArgument("env_manager", default_value="false", description="Launch env_manager?")
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument("launch_sim", default_value="false", description="Launch simulation?")
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument("launch_moveit", default_value="true", description="Launch moveit?")
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument("launch_perception", default_value="false", description="Launch perception?")
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument("launch_task_planner", default_value="false", description="Launch task_planner?")
|
||||
)
|
||||
|
||||
# Initialize Arguments
|
||||
rbs_robot_type = LaunchConfiguration("rbs_robot_type")
|
||||
|
@ -180,6 +192,10 @@ def generate_launch_description():
|
|||
start_joint_controller = LaunchConfiguration("start_joint_controller")
|
||||
initial_joint_controller = LaunchConfiguration("initial_joint_controller")
|
||||
launch_rviz = LaunchConfiguration("launch_rviz")
|
||||
launch_simulation = LaunchConfiguration("launch_sim")
|
||||
launch_moveit = LaunchConfiguration("launch_moveit")
|
||||
launch_task_planner = LaunchConfiguration("launch_task_planner")
|
||||
launch_perception = LaunchConfiguration("launch_perception")
|
||||
moveit_config_package = LaunchConfiguration("moveit_config_package")
|
||||
moveit_config_file = LaunchConfiguration("moveit_config_file")
|
||||
use_sim_time = LaunchConfiguration("use_sim_time")
|
||||
|
@ -225,6 +241,23 @@ def generate_launch_description():
|
|||
)
|
||||
robot_description = {"robot_description": robot_description_content}
|
||||
|
||||
# MoveIt Configuration
|
||||
robot_description_semantic_content = Command(
|
||||
[
|
||||
PathJoinSubstitution([FindExecutable(name="xacro")]),
|
||||
" ",
|
||||
PathJoinSubstitution(
|
||||
[FindPackageShare(moveit_config_package), "srdf", moveit_config_file]
|
||||
), " ",
|
||||
"name:=", "ur", " ",
|
||||
"prefix:=", prefix, " ",
|
||||
"with_gripper:=", with_gripper_condition
|
||||
]
|
||||
)
|
||||
robot_description_semantic = {"robot_description_semantic": robot_description_semantic_content}
|
||||
robot_description_kinematics = PathJoinSubstitution(
|
||||
[FindPackageShare(moveit_config_package), "config", "kinematics.yaml"]
|
||||
)
|
||||
robot_state_publisher = Node(
|
||||
package="robot_state_publisher",
|
||||
executable="robot_state_publisher",
|
||||
|
@ -239,9 +272,11 @@ def generate_launch_description():
|
|||
output="log",
|
||||
arguments=["-d", rviz_config_file],
|
||||
parameters=[
|
||||
robot_description
|
||||
robot_description,
|
||||
robot_description_semantic,
|
||||
robot_description_kinematics
|
||||
],
|
||||
condition=IfCondition(launch_rviz),)
|
||||
condition=IfCondition(launch_rviz))
|
||||
|
||||
control = IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource([
|
||||
|
@ -253,7 +288,7 @@ def generate_launch_description():
|
|||
]),
|
||||
launch_arguments={
|
||||
'with_gripper': with_gripper_condition,
|
||||
'robot_description': robot_description,
|
||||
'robot_description': robot_description_content,
|
||||
'start_joint_controller': start_joint_controller,
|
||||
'initial_joint_controller': initial_joint_controller,
|
||||
'controllers_file': controllers_file
|
||||
|
@ -271,7 +306,8 @@ def generate_launch_description():
|
|||
'sim_gazebo': sim_gazebo,
|
||||
'rbs_robot_type': rbs_robot_type,
|
||||
'env_manager': env_manager
|
||||
}.items())
|
||||
}.items(),
|
||||
condition=IfCondition(launch_simulation))
|
||||
|
||||
moveit = IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource([
|
||||
|
@ -282,13 +318,15 @@ def generate_launch_description():
|
|||
])
|
||||
]),
|
||||
launch_arguments={
|
||||
'robot_description': robot_description,
|
||||
'robot_description': robot_description_content,
|
||||
'moveit_config_package': moveit_config_package,
|
||||
'moveit_config_file': moveit_config_file,
|
||||
'use_sim_time': use_sim_time,
|
||||
'prefix': prefix,
|
||||
'with_gripper': with_gripper_condition
|
||||
}.items())
|
||||
'with_gripper': with_gripper_condition,
|
||||
'robot_description_semantic': robot_description_semantic_content
|
||||
}.items(),
|
||||
condition=IfCondition(launch_moveit))
|
||||
|
||||
task_planner = IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource([
|
||||
|
@ -300,19 +338,8 @@ def generate_launch_description():
|
|||
]),
|
||||
launch_arguments={
|
||||
# TBD
|
||||
}.items())
|
||||
|
||||
task_planner = IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource([
|
||||
PathJoinSubstitution([
|
||||
FindPackageShare('rbs_task_planner'),
|
||||
'launch',
|
||||
'task_planner.launch.py'
|
||||
])
|
||||
]),
|
||||
launch_arguments={
|
||||
# TBD
|
||||
}.items())
|
||||
}.items(),
|
||||
condition=IfCondition(launch_task_planner))
|
||||
|
||||
perception = IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource([
|
||||
|
@ -324,7 +351,8 @@ def generate_launch_description():
|
|||
]),
|
||||
launch_arguments={
|
||||
# TBD
|
||||
}.items())
|
||||
}.items(),
|
||||
condition=IfCondition(launch_perception))
|
||||
|
||||
nodes_to_start = [
|
||||
robot_state_publisher,
|
||||
|
|
|
@ -43,7 +43,7 @@ def generate_launch_description():
|
|||
description="YAML file with the controllers configuration.",
|
||||
)
|
||||
)
|
||||
robot_description = LaunchConfiguration("robot_description")
|
||||
robot_description_content = LaunchConfiguration("robot_description")
|
||||
runtime_config_package = LaunchConfiguration("runtime_config_package")
|
||||
controllers_file = LaunchConfiguration("controllers_file")
|
||||
start_joint_controller = LaunchConfiguration("start_joint_controller")
|
||||
|
@ -53,6 +53,7 @@ def generate_launch_description():
|
|||
initial_joint_controllers_file_path = PathJoinSubstitution(
|
||||
[FindPackageShare(runtime_config_package), "config", controllers_file]
|
||||
)
|
||||
robot_description = {"robot_description": robot_description_content}
|
||||
|
||||
control_node = Node(
|
||||
package="controller_manager",
|
||||
|
|
|
@ -16,7 +16,14 @@ def generate_launch_description():
|
|||
DeclareLaunchArgument(
|
||||
"robot_description",
|
||||
default_value="",
|
||||
description="robot description param",
|
||||
description="robot description string",
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument(
|
||||
"robot_description_semantic",
|
||||
default_value="",
|
||||
description="robot description semantic string",
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
|
@ -63,21 +70,10 @@ def generate_launch_description():
|
|||
moveit_config_file = LaunchConfiguration("moveit_config_file")
|
||||
use_sim_time = LaunchConfiguration("use_sim_time")
|
||||
with_gripper_condition = LaunchConfiguration("with_gripper")
|
||||
robot_description = LaunchConfiguration("robot_description")
|
||||
|
||||
# MoveIt Configuration
|
||||
robot_description_semantic_content = Command(
|
||||
[
|
||||
PathJoinSubstitution([FindExecutable(name="xacro")]),
|
||||
" ",
|
||||
PathJoinSubstitution(
|
||||
[FindPackageShare(moveit_config_package), "srdf", moveit_config_file]
|
||||
), " ",
|
||||
"name:=", "ur", " ",
|
||||
"prefix:=", prefix, " ",
|
||||
"with_gripper:=", with_gripper_condition
|
||||
]
|
||||
)
|
||||
robot_description_content = LaunchConfiguration("robot_description")
|
||||
robot_description_semantic_content = LaunchConfiguration("robot_description_semantic")
|
||||
|
||||
robot_description = {"robot_description": robot_description_content}
|
||||
robot_description_semantic = {"robot_description_semantic": robot_description_semantic_content}
|
||||
use_sim_time = {"use_sim_time": use_sim_time}
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue