add external robot_description parameter for rbs_robot.launch.py
feat(robot): add support for handling scalar joint positions - Updated `RobotData` and `RbsArm` to allow joint positions to be passed as either a list or a scalar value. - Refactored logic to dynamically handle scalar values and repeat them across all joints. - Added new `initial_arm_joint_positions` and `initial_gripper_joint_positions` properties in `RbsArm`. - Improved joint position initialization in the `Scene` class to retrieve robot description asynchronously if not provided. - Enhanced the launch script to configure environment variables based on available CPU cores. - Minor code cleanups and bug fixes, including terrain naming and corrected joint defaultsd. git commit --amend
This commit is contained in:
parent
bc8745abe5
commit
e4e3e4e3af
18 changed files with 686 additions and 342 deletions
|
@ -1,20 +1,23 @@
|
|||
from launch import LaunchContext, LaunchDescription
|
||||
import os
|
||||
|
||||
import xacro
|
||||
from ament_index_python.packages import get_package_share_directory
|
||||
from launch import LaunchDescription
|
||||
from launch.actions import (
|
||||
DeclareLaunchArgument,
|
||||
IncludeLaunchDescription,
|
||||
RegisterEventHandler,
|
||||
OpaqueFunction
|
||||
OpaqueFunction,
|
||||
)
|
||||
from launch.event_handlers import OnProcessExit
|
||||
from launch.conditions import IfCondition
|
||||
from launch.launch_description_sources import PythonLaunchDescriptionSource
|
||||
from launch.substitutions import Command, FindExecutable, LaunchConfiguration, PathJoinSubstitution
|
||||
from launch.substitutions import (
|
||||
Command,
|
||||
FindExecutable,
|
||||
LaunchConfiguration,
|
||||
PathJoinSubstitution,
|
||||
)
|
||||
from launch_ros.actions import Node
|
||||
from launch_ros.substitutions import FindPackageShare
|
||||
import xacro
|
||||
import os
|
||||
from ament_index_python.packages import get_package_share_directory
|
||||
from rbs_launch_utils.launch_common import load_yaml
|
||||
|
||||
|
||||
def launch_setup(context, *args, **kwargs):
|
||||
|
@ -54,31 +57,39 @@ def launch_setup(context, *args, **kwargs):
|
|||
description_file = description_file.perform(context)
|
||||
controllers_file = controllers_file.perform(context)
|
||||
multi_robot = multi_robot.perform(context)
|
||||
robot_description = LaunchConfiguration("robot_description")
|
||||
|
||||
remappings = []
|
||||
if multi_robot == "true":
|
||||
remappings.append([("/tf", "tf"), ("/tf_static", "tf_static")])
|
||||
|
||||
controllers_file = os.path.join(get_package_share_directory(description_package), "config", controllers_file)
|
||||
|
||||
xacro_file = os.path.join(get_package_share_directory(description_package), "urdf", description_file)
|
||||
robot_description_doc = xacro.process_file(
|
||||
xacro_file,
|
||||
mappings={
|
||||
"gripper_name": gripper_name.perform(context),
|
||||
"hardware": hardware.perform(context),
|
||||
"simulation_controllers": controllers_file,
|
||||
"namespace": namespace,
|
||||
"x": x_pos.perform(context),
|
||||
"y": y_pos.perform(context),
|
||||
"z": z_pos.perform(context),
|
||||
"roll": roll.perform(context),
|
||||
"pitch": pitch.perform(context),
|
||||
"yaw": yaw.perform(context)
|
||||
}
|
||||
controllers_file = os.path.join(
|
||||
get_package_share_directory(description_package), "config", controllers_file
|
||||
)
|
||||
|
||||
robot_description_content = robot_description_doc.toprettyxml(indent=" ")
|
||||
if robot_description.perform(context):
|
||||
xacro_file = os.path.join(
|
||||
get_package_share_directory(description_package), "urdf", description_file
|
||||
)
|
||||
robot_description_doc = xacro.process_file(
|
||||
xacro_file,
|
||||
mappings={
|
||||
"gripper_name": gripper_name.perform(context),
|
||||
"hardware": hardware.perform(context),
|
||||
"simulation_controllers": controllers_file,
|
||||
"namespace": namespace,
|
||||
"x": x_pos.perform(context),
|
||||
"y": y_pos.perform(context),
|
||||
"z": z_pos.perform(context),
|
||||
"roll": roll.perform(context),
|
||||
"pitch": pitch.perform(context),
|
||||
"yaw": yaw.perform(context),
|
||||
},
|
||||
)
|
||||
|
||||
robot_description_content = robot_description_doc.toprettyxml(indent=" ")
|
||||
else:
|
||||
robot_description_content = robot_description.perform(context)
|
||||
|
||||
robot_description = {"robot_description": robot_description_content}
|
||||
|
||||
|
@ -87,23 +98,37 @@ def launch_setup(context, *args, **kwargs):
|
|||
PathJoinSubstitution([FindExecutable(name="xacro")]),
|
||||
" ",
|
||||
PathJoinSubstitution(
|
||||
[FindPackageShare(moveit_config_package), "config/moveit", "rbs_arm.srdf.xacro"]
|
||||
[
|
||||
FindPackageShare(moveit_config_package),
|
||||
"config/moveit",
|
||||
"rbs_arm.srdf.xacro",
|
||||
]
|
||||
),
|
||||
" ",
|
||||
"name:=",robot_type," ",
|
||||
"with_gripper:=",with_gripper_condition, " ",
|
||||
"gripper_name:=", gripper_name, " ",
|
||||
"name:=",
|
||||
robot_type,
|
||||
" ",
|
||||
"with_gripper:=",
|
||||
with_gripper_condition,
|
||||
" ",
|
||||
"gripper_name:=",
|
||||
gripper_name,
|
||||
" ",
|
||||
]
|
||||
)
|
||||
|
||||
robot_description_semantic = {"robot_description_semantic": robot_description_semantic_content}
|
||||
robot_description_semantic = {
|
||||
"robot_description_semantic": robot_description_semantic_content
|
||||
}
|
||||
robot_description_kinematics = PathJoinSubstitution(
|
||||
[FindPackageShare(moveit_config_package), "config", "kinematics.yaml"]
|
||||
)
|
||||
|
||||
# kinematics_yaml = load_yaml("rbs_arm", "config/kinematics.yaml")
|
||||
|
||||
robot_description_kinematics = {"robot_description_kinematics": robot_description_kinematics}
|
||||
robot_description_kinematics = {
|
||||
"robot_description_kinematics": robot_description_kinematics
|
||||
}
|
||||
rviz_config_file = PathJoinSubstitution(
|
||||
[FindPackageShare("rbs_bringup"), "config", "rbs.rviz"]
|
||||
)
|
||||
|
@ -131,108 +156,119 @@ def launch_setup(context, *args, **kwargs):
|
|||
robot_description,
|
||||
robot_description_semantic,
|
||||
robot_description_kinematics,
|
||||
{'use_sim_time': use_sim_time}
|
||||
{"use_sim_time": use_sim_time},
|
||||
],
|
||||
condition=IfCondition(launch_rviz)
|
||||
condition=IfCondition(launch_rviz),
|
||||
)
|
||||
|
||||
rviz = Node(
|
||||
package="rviz2",
|
||||
executable="rviz2",
|
||||
name="rviz2",
|
||||
output="log",
|
||||
arguments=["-d", rviz_config_file],
|
||||
parameters=[
|
||||
robot_description,
|
||||
robot_description_semantic,
|
||||
robot_description_kinematics
|
||||
],
|
||||
condition=IfCondition(launch_rviz))
|
||||
|
||||
control = IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource([
|
||||
PathJoinSubstitution([
|
||||
FindPackageShare(description_package),
|
||||
'launch',
|
||||
'control.launch.py'
|
||||
])
|
||||
]),
|
||||
PythonLaunchDescriptionSource(
|
||||
[
|
||||
PathJoinSubstitution(
|
||||
[
|
||||
FindPackageShare(description_package),
|
||||
"launch",
|
||||
"control.launch.py",
|
||||
]
|
||||
)
|
||||
]
|
||||
),
|
||||
launch_arguments={
|
||||
'control_space': "task",
|
||||
'control_strategy': "effort",
|
||||
'is_gripper': "false",
|
||||
'namespace': namespace,
|
||||
"control_space": "task",
|
||||
"control_strategy": "effort",
|
||||
"has_gripper": "true",
|
||||
"namespace": namespace,
|
||||
}.items(),
|
||||
condition=IfCondition(launch_controllers))
|
||||
condition=IfCondition(launch_controllers),
|
||||
)
|
||||
|
||||
moveit = IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource([
|
||||
PathJoinSubstitution([
|
||||
FindPackageShare(moveit_config_package),
|
||||
'launch',
|
||||
'moveit.launch.py'
|
||||
])
|
||||
]),
|
||||
PythonLaunchDescriptionSource(
|
||||
[
|
||||
PathJoinSubstitution(
|
||||
[
|
||||
FindPackageShare(moveit_config_package),
|
||||
"launch",
|
||||
"moveit.launch.py",
|
||||
]
|
||||
)
|
||||
]
|
||||
),
|
||||
launch_arguments={
|
||||
'robot_description': robot_description_content,
|
||||
'moveit_config_package': moveit_config_package,
|
||||
'moveit_config_file': moveit_config_file,
|
||||
'use_sim_time': use_sim_time,
|
||||
'tf_prefix': robot_name,
|
||||
'with_gripper': with_gripper_condition,
|
||||
'robot_description_semantic': robot_description_semantic_content,
|
||||
'namespace': namespace,
|
||||
"robot_description": robot_description_content,
|
||||
"moveit_config_package": moveit_config_package,
|
||||
"moveit_config_file": moveit_config_file,
|
||||
"use_sim_time": use_sim_time,
|
||||
"tf_prefix": robot_name,
|
||||
"with_gripper": with_gripper_condition,
|
||||
"robot_description_semantic": robot_description_semantic_content,
|
||||
"namespace": namespace,
|
||||
}.items(),
|
||||
condition=IfCondition(launch_moveit))
|
||||
condition=IfCondition(launch_moveit),
|
||||
)
|
||||
|
||||
skills = IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource([
|
||||
PathJoinSubstitution([
|
||||
FindPackageShare('rbs_skill_servers'),
|
||||
'launch',
|
||||
'skills.launch.py'
|
||||
])
|
||||
]),
|
||||
PythonLaunchDescriptionSource(
|
||||
[
|
||||
PathJoinSubstitution(
|
||||
[
|
||||
FindPackageShare("rbs_skill_servers"),
|
||||
"launch",
|
||||
"skills.launch.py",
|
||||
]
|
||||
)
|
||||
]
|
||||
),
|
||||
launch_arguments={
|
||||
'robot_description': robot_description_content,
|
||||
'robot_description_semantic': robot_description_semantic_content,
|
||||
'robot_description_kinematics': robot_description_kinematics,
|
||||
'use_sim_time': use_sim_time,
|
||||
'with_gripper_condition': with_gripper_condition,
|
||||
'namespace': namespace
|
||||
}.items()
|
||||
"robot_description": robot_description_content,
|
||||
"robot_description_semantic": robot_description_semantic_content,
|
||||
"robot_description_kinematics": robot_description_kinematics,
|
||||
"use_sim_time": use_sim_time,
|
||||
"with_gripper_condition": with_gripper_condition,
|
||||
"namespace": namespace,
|
||||
}.items(),
|
||||
)
|
||||
|
||||
task_planner = IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource([
|
||||
PathJoinSubstitution([
|
||||
FindPackageShare('rbs_task_planner'),
|
||||
'launch',
|
||||
'task_planner.launch.py'
|
||||
])
|
||||
]),
|
||||
PythonLaunchDescriptionSource(
|
||||
[
|
||||
PathJoinSubstitution(
|
||||
[
|
||||
FindPackageShare("rbs_task_planner"),
|
||||
"launch",
|
||||
"task_planner.launch.py",
|
||||
]
|
||||
)
|
||||
]
|
||||
),
|
||||
launch_arguments={
|
||||
# TBD
|
||||
}.items(),
|
||||
condition=IfCondition(launch_task_planner))
|
||||
condition=IfCondition(launch_task_planner),
|
||||
)
|
||||
|
||||
perception = IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource([
|
||||
PathJoinSubstitution([
|
||||
FindPackageShare('rbs_perception'),
|
||||
'launch',
|
||||
'perception.launch.py'
|
||||
])
|
||||
]),
|
||||
PythonLaunchDescriptionSource(
|
||||
[
|
||||
PathJoinSubstitution(
|
||||
[
|
||||
FindPackageShare("rbs_perception"),
|
||||
"launch",
|
||||
"perception.launch.py",
|
||||
]
|
||||
)
|
||||
]
|
||||
),
|
||||
launch_arguments={
|
||||
# TBD
|
||||
}.items(),
|
||||
condition=IfCondition(launch_perception))
|
||||
condition=IfCondition(launch_perception),
|
||||
)
|
||||
|
||||
asm_config = Node(
|
||||
package="rbs_utils",
|
||||
namespace=namespace,
|
||||
executable="assembly_config_service.py"
|
||||
executable="assembly_config_service.py",
|
||||
)
|
||||
|
||||
nodes_to_start = [
|
||||
|
@ -243,7 +279,7 @@ def launch_setup(context, *args, **kwargs):
|
|||
asm_config,
|
||||
# task_planner,
|
||||
# perception,
|
||||
rviz
|
||||
rviz,
|
||||
]
|
||||
return nodes_to_start
|
||||
|
||||
|
@ -254,7 +290,7 @@ def generate_launch_description():
|
|||
DeclareLaunchArgument(
|
||||
"robot_type",
|
||||
description="Type of robot by name",
|
||||
choices=["rbs_arm","ur3", "ur3e", "ur5", "ur5e", "ur10", "ur10e", "ur16e"],
|
||||
choices=["rbs_arm", "ur3", "ur3e", "ur5", "ur5e", "ur10", "ur10e", "ur16e"],
|
||||
default_value="rbs_arm",
|
||||
)
|
||||
)
|
||||
|
@ -336,126 +372,145 @@ def generate_launch_description():
|
|||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument("with_gripper",
|
||||
default_value="true",
|
||||
description="With gripper or not?")
|
||||
DeclareLaunchArgument(
|
||||
"with_gripper", default_value="true", description="With gripper or not?"
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument("launch_rviz",
|
||||
default_value="false",
|
||||
description="Launch RViz?")
|
||||
DeclareLaunchArgument(
|
||||
"launch_rviz", default_value="false", description="Launch RViz?"
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument("sim_gazebo",
|
||||
default_value="true",
|
||||
description="Gazebo Simulation")
|
||||
DeclareLaunchArgument(
|
||||
"sim_gazebo", default_value="true", description="Gazebo Simulation"
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument("env_manager",
|
||||
default_value="true",
|
||||
description="Launch env_manager?")
|
||||
DeclareLaunchArgument(
|
||||
"env_manager", default_value="true", description="Launch env_manager?"
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument("launch_sim",
|
||||
default_value="true",
|
||||
description="Launch simulator (Gazebo)?\
|
||||
Most general arg")
|
||||
DeclareLaunchArgument(
|
||||
"launch_sim",
|
||||
default_value="true",
|
||||
description="Launch simulator (Gazebo)?\
|
||||
Most general arg",
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument("launch_moveit",
|
||||
default_value="true",
|
||||
description="Launch moveit?")
|
||||
DeclareLaunchArgument(
|
||||
"launch_moveit", default_value="true", description="Launch moveit?"
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument("launch_perception",
|
||||
default_value="false",
|
||||
description="Launch perception?")
|
||||
DeclareLaunchArgument(
|
||||
"launch_perception", default_value="false", description="Launch perception?"
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument("launch_task_planner",
|
||||
default_value="false",
|
||||
description="Launch task_planner?")
|
||||
DeclareLaunchArgument(
|
||||
"launch_task_planner",
|
||||
default_value="false",
|
||||
description="Launch task_planner?",
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument("cartesian_controllers",
|
||||
default_value="false",
|
||||
description="Load cartesian\
|
||||
controllers?")
|
||||
DeclareLaunchArgument(
|
||||
"cartesian_controllers",
|
||||
default_value="false",
|
||||
description="Load cartesian\
|
||||
controllers?",
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument("hardware",
|
||||
choices=["gazebo", "mock"],
|
||||
default_value="gazebo",
|
||||
description="Choose your harware_interface")
|
||||
DeclareLaunchArgument(
|
||||
"hardware",
|
||||
choices=["gazebo", "mock"],
|
||||
default_value="gazebo",
|
||||
description="Choose your harware_interface",
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument("launch_controllers",
|
||||
default_value="true",
|
||||
description="Launch controllers?")
|
||||
DeclareLaunchArgument(
|
||||
"launch_controllers",
|
||||
default_value="true",
|
||||
description="Launch controllers?",
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument("gazebo_gui",
|
||||
default_value="false",
|
||||
description="Launch gazebo with gui?")
|
||||
DeclareLaunchArgument(
|
||||
"gazebo_gui", default_value="false", description="Launch gazebo with gui?"
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument("namespace",
|
||||
default_value="",
|
||||
description="The ROS2 namespace of a robot")
|
||||
DeclareLaunchArgument(
|
||||
"namespace", default_value="", description="The ROS2 namespace of a robot"
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument("x",
|
||||
default_value="0.0",
|
||||
description="Position of robot in world by X")
|
||||
DeclareLaunchArgument(
|
||||
"x", default_value="0.0", description="Position of robot in world by X"
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument("y",
|
||||
default_value="0.0",
|
||||
description="Position of robot in world by Y")
|
||||
DeclareLaunchArgument(
|
||||
"y", default_value="0.0", description="Position of robot in world by Y"
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument("z",
|
||||
default_value="0.0",
|
||||
description="Position of robot in world by Z")
|
||||
DeclareLaunchArgument(
|
||||
"z", default_value="0.0", description="Position of robot in world by Z"
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument("roll",
|
||||
default_value="0.0",
|
||||
description="Position of robot in world by Z")
|
||||
DeclareLaunchArgument(
|
||||
"roll", default_value="0.0", description="Position of robot in world by Z"
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument("pitch",
|
||||
default_value="0.0",
|
||||
description="Position of robot in world by Z")
|
||||
DeclareLaunchArgument(
|
||||
"pitch", default_value="0.0", description="Position of robot in world by Z"
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument("yaw",
|
||||
default_value="0.0",
|
||||
description="Position of robot in world by Z")
|
||||
DeclareLaunchArgument(
|
||||
"yaw", default_value="0.0", description="Position of robot in world by Z"
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument("roll",
|
||||
default_value="0.0",
|
||||
description="Position of robot in world by Z")
|
||||
DeclareLaunchArgument(
|
||||
"roll", default_value="0.0", description="Position of robot in world by Z"
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument("pitch",
|
||||
default_value="0.0",
|
||||
description="Position of robot in world by Z")
|
||||
DeclareLaunchArgument(
|
||||
"pitch", default_value="0.0", description="Position of robot in world by Z"
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument("yaw",
|
||||
default_value="0.0",
|
||||
description="Position of robot in world by Z")
|
||||
DeclareLaunchArgument(
|
||||
"yaw", default_value="0.0", description="Position of robot in world by Z"
|
||||
)
|
||||
)
|
||||
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument(
|
||||
"multi_robot",
|
||||
default_value="false",
|
||||
description="Flag if you use multi robot setup"
|
||||
description="Flag if you use multi robot setup",
|
||||
)
|
||||
)
|
||||
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument(
|
||||
"robot_description",
|
||||
default_value="",
|
||||
description="Robot description that override internal robot desctioption",
|
||||
)
|
||||
)
|
||||
|
||||
return LaunchDescription(declared_arguments + [OpaqueFunction(function=launch_setup)])
|
||||
return LaunchDescription(
|
||||
declared_arguments + [OpaqueFunction(function=launch_setup)]
|
||||
)
|
||||
|
|
|
@ -1,17 +1,18 @@
|
|||
import os
|
||||
|
||||
from ament_index_python.packages import get_package_share_directory
|
||||
from launch import LaunchDescription
|
||||
from launch.actions import (
|
||||
DeclareLaunchArgument,
|
||||
IncludeLaunchDescription,
|
||||
OpaqueFunction
|
||||
OpaqueFunction,
|
||||
)
|
||||
from launch.conditions import IfCondition
|
||||
from launch.launch_description_sources import PythonLaunchDescriptionSource
|
||||
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
|
||||
from launch_ros.substitutions import FindPackageShare
|
||||
from launch_ros.actions import Node
|
||||
import os
|
||||
from ament_index_python.packages import get_package_share_directory
|
||||
# from nav2_common.launch import RewrittenYaml
|
||||
from launch_ros.substitutions import FindPackageShare
|
||||
|
||||
|
||||
def launch_setup(context, *args, **kwargs):
|
||||
# Initialize Arguments
|
||||
|
@ -39,32 +40,35 @@ def launch_setup(context, *args, **kwargs):
|
|||
gazebo_gui = LaunchConfiguration("gazebo_gui")
|
||||
gripper_name = LaunchConfiguration("gripper_name")
|
||||
|
||||
|
||||
sim_gazebo = LaunchConfiguration("sim_gazebo")
|
||||
launch_simulation = LaunchConfiguration("launch_sim")
|
||||
simulation = IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource([
|
||||
PathJoinSubstitution([
|
||||
FindPackageShare('rbs_simulation'),
|
||||
'launch',
|
||||
'simulation_gazebo.launch.py'
|
||||
])
|
||||
]),
|
||||
PythonLaunchDescriptionSource(
|
||||
[
|
||||
PathJoinSubstitution(
|
||||
[
|
||||
FindPackageShare("rbs_simulation"),
|
||||
"launch",
|
||||
"simulation_gazebo.launch.py",
|
||||
]
|
||||
)
|
||||
]
|
||||
),
|
||||
launch_arguments={
|
||||
'sim_gazebo': sim_gazebo,
|
||||
'debugger': "false",
|
||||
'launch_env_manager': env_manager,
|
||||
'gazebo_world_filename': "asm2.sdf"
|
||||
"sim_gazebo": sim_gazebo,
|
||||
"debugger": "false",
|
||||
"launch_env_manager": env_manager,
|
||||
"gazebo_world_filename": "asm2.sdf",
|
||||
}.items(),
|
||||
condition=IfCondition(launch_simulation)
|
||||
condition=IfCondition(launch_simulation),
|
||||
)
|
||||
|
||||
# FIXME: namespaces
|
||||
# configured_params = RewrittenYaml(
|
||||
# source_file=os.path.join(
|
||||
# get_package_share_directory(
|
||||
# description_package.perform(context)),
|
||||
# "config",
|
||||
# description_package.perform(context)),
|
||||
# "config",
|
||||
# controllers_file.perform(context)),
|
||||
# root_key=robot_name.perform(context),
|
||||
# param_rewrites={},
|
||||
|
@ -72,34 +76,38 @@ def launch_setup(context, *args, **kwargs):
|
|||
# )
|
||||
|
||||
initial_joint_controllers_file_path = os.path.join(
|
||||
get_package_share_directory('rbs_arm'), 'config', 'rbs_arm0_controllers.yaml'
|
||||
get_package_share_directory("rbs_arm"), "config", "rbs_arm0_controllers.yaml"
|
||||
)
|
||||
|
||||
# controller_paramfile = configured_params.perform(context)
|
||||
# controller_paramfile = PathJoinSubstitution([
|
||||
# FindPackageShare(robot_type), "config", "rbs_arm0_controllers.yaml"
|
||||
# ])
|
||||
# namespace = "/" + robot_name.perform(context)
|
||||
# namespace = "/" + robot_name.perform(context)
|
||||
namespace = ""
|
||||
|
||||
gz_spawner = Node(
|
||||
package='ros_gz_sim',
|
||||
executable='create',
|
||||
package="ros_gz_sim",
|
||||
executable="create",
|
||||
# prefix=['gdbserver localhost:1234'],
|
||||
arguments=[
|
||||
'-name', robot_name.perform(context),
|
||||
'-topic', namespace + '/robot_description'],
|
||||
output='screen',
|
||||
condition=IfCondition(sim_gazebo))
|
||||
"-name",
|
||||
robot_name.perform(context),
|
||||
"-topic",
|
||||
namespace + "/robot_description",
|
||||
],
|
||||
output="screen",
|
||||
condition=IfCondition(sim_gazebo),
|
||||
)
|
||||
|
||||
single_robot_setup = IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource([
|
||||
PathJoinSubstitution([
|
||||
FindPackageShare('rbs_bringup'),
|
||||
"launch",
|
||||
"rbs_robot.launch.py"
|
||||
])
|
||||
]),
|
||||
PythonLaunchDescriptionSource(
|
||||
[
|
||||
PathJoinSubstitution(
|
||||
[FindPackageShare("rbs_bringup"), "launch", "rbs_robot.launch.py"]
|
||||
)
|
||||
]
|
||||
),
|
||||
launch_arguments={
|
||||
"env_manager": env_manager,
|
||||
"with_gripper": with_gripper_condition,
|
||||
|
@ -127,14 +135,10 @@ def launch_setup(context, *args, **kwargs):
|
|||
# "x": "0.5",
|
||||
# "y": "0.5",
|
||||
# "z": "0.5"
|
||||
}.items()
|
||||
}.items(),
|
||||
)
|
||||
|
||||
nodes_to_start = [
|
||||
simulation,
|
||||
gz_spawner,
|
||||
single_robot_setup
|
||||
]
|
||||
|
||||
nodes_to_start = [simulation, gz_spawner, single_robot_setup]
|
||||
return nodes_to_start
|
||||
|
||||
|
||||
|
@ -144,7 +148,7 @@ def generate_launch_description():
|
|||
DeclareLaunchArgument(
|
||||
"robot_type",
|
||||
description="Type of robot by name",
|
||||
choices=["rbs_arm","ur3", "ur3e", "ur5", "ur5e", "ur10", "ur10e", "ur16e"],
|
||||
choices=["rbs_arm", "ur3", "ur3e", "ur5", "ur5e", "ur10", "ur10e", "ur16e"],
|
||||
default_value="rbs_arm",
|
||||
)
|
||||
)
|
||||
|
@ -224,62 +228,74 @@ def generate_launch_description():
|
|||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument("with_gripper",
|
||||
default_value="true",
|
||||
description="With gripper or not?")
|
||||
DeclareLaunchArgument(
|
||||
"with_gripper", default_value="true", description="With gripper or not?"
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument("sim_gazebo",
|
||||
default_value="true",
|
||||
description="Gazebo Simulation")
|
||||
DeclareLaunchArgument(
|
||||
"sim_gazebo", default_value="true", description="Gazebo Simulation"
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument("env_manager",
|
||||
default_value="true",
|
||||
description="Launch env_manager?")
|
||||
DeclareLaunchArgument(
|
||||
"env_manager", default_value="true", description="Launch env_manager?"
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument("launch_sim",
|
||||
default_value="true",
|
||||
description="Launch simulator (Gazebo)?\
|
||||
Most general arg")
|
||||
DeclareLaunchArgument(
|
||||
"launch_sim",
|
||||
default_value="true",
|
||||
description="Launch simulator (Gazebo)?\
|
||||
Most general arg",
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument("launch_moveit",
|
||||
default_value="false",
|
||||
description="Launch moveit?")
|
||||
DeclareLaunchArgument(
|
||||
"launch_moveit", default_value="false", description="Launch moveit?"
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument("launch_perception",
|
||||
default_value="false",
|
||||
description="Launch perception?")
|
||||
DeclareLaunchArgument(
|
||||
"launch_perception", default_value="false", description="Launch perception?"
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument("launch_task_planner",
|
||||
default_value="false",
|
||||
description="Launch task_planner?")
|
||||
DeclareLaunchArgument(
|
||||
"launch_task_planner",
|
||||
default_value="false",
|
||||
description="Launch task_planner?",
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument("cartesian_controllers",
|
||||
default_value="true",
|
||||
description="Load cartesian\
|
||||
controllers?")
|
||||
DeclareLaunchArgument(
|
||||
"cartesian_controllers",
|
||||
default_value="true",
|
||||
description="Load cartesian\
|
||||
controllers?",
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument("hardware",
|
||||
choices=["gazebo", "mock"],
|
||||
default_value="gazebo",
|
||||
description="Choose your harware_interface")
|
||||
DeclareLaunchArgument(
|
||||
"hardware",
|
||||
choices=["gazebo", "mock"],
|
||||
default_value="gazebo",
|
||||
description="Choose your harware_interface",
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument("launch_controllers",
|
||||
default_value="true",
|
||||
description="Launch controllers?")
|
||||
DeclareLaunchArgument(
|
||||
"launch_controllers",
|
||||
default_value="true",
|
||||
description="Launch controllers?",
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument("gazebo_gui",
|
||||
default_value="true",
|
||||
description="Launch gazebo with gui?")
|
||||
DeclareLaunchArgument(
|
||||
"gazebo_gui", default_value="true", description="Launch gazebo with gui?"
|
||||
)
|
||||
)
|
||||
|
||||
return LaunchDescription(declared_arguments + [OpaqueFunction(function=launch_setup)])
|
||||
return LaunchDescription(
|
||||
declared_arguments + [OpaqueFunction(function=launch_setup)]
|
||||
)
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue