refactoring repo
This commit is contained in:
parent
6fa469be36
commit
f76340d78a
68 changed files with 5 additions and 6275 deletions
|
@ -281,7 +281,7 @@ def generate_launch_description():
|
|||
control = IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource([
|
||||
PathJoinSubstitution([
|
||||
FindPackageShare('rbs_bringup'),
|
||||
FindPackageShare('ur_description'),
|
||||
'launch',
|
||||
'control.launch.py'
|
||||
])
|
||||
|
@ -297,7 +297,7 @@ def generate_launch_description():
|
|||
simulation = IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource([
|
||||
PathJoinSubstitution([
|
||||
FindPackageShare('rbs_bringup'),
|
||||
FindPackageShare('rbs_simulation'),
|
||||
'launch',
|
||||
'simulation.launch.py'
|
||||
])
|
||||
|
@ -312,7 +312,7 @@ def generate_launch_description():
|
|||
moveit = IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource([
|
||||
PathJoinSubstitution([
|
||||
FindPackageShare('rbs_bringup'),
|
||||
FindPackageShare('ur_moveit_config'),
|
||||
'launch',
|
||||
'moveit.launch.py'
|
||||
])
|
||||
|
@ -344,7 +344,7 @@ def generate_launch_description():
|
|||
perception = IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource([
|
||||
PathJoinSubstitution([
|
||||
FindPackageShare('rbs_bringup'),
|
||||
FindPackageShare('rbs_perception'),
|
||||
'launch',
|
||||
'perception.launch.py'
|
||||
])
|
||||
|
|
|
@ -1,125 +0,0 @@
|
|||
from launch_ros.actions import Node
|
||||
from launch import LaunchDescription
|
||||
from launch.actions import DeclareLaunchArgument, ExecuteProcess
|
||||
from launch_ros.substitutions import FindPackageShare
|
||||
from launch.substitutions import Command, FindExecutable, LaunchConfiguration, PathJoinSubstitution
|
||||
from launch.conditions import IfCondition, UnlessCondition
|
||||
|
||||
|
||||
def generate_launch_description():
|
||||
declared_arguments = []
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument(
|
||||
"with_gripper",
|
||||
default_value="false",
|
||||
description="With gripper or not?",
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument(
|
||||
"robot_description",
|
||||
default_value="",
|
||||
description="robot description param",
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument(
|
||||
"start_joint_controller",
|
||||
default_value="false",
|
||||
description="Enable headless mode for robot control",
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument(
|
||||
"initial_joint_controller",
|
||||
default_value="joint_trajectory_controller",
|
||||
description="Robot controller to start.",
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument(
|
||||
"controllers_file",
|
||||
default_value="ur_controllers.yaml",
|
||||
description="YAML file with the controllers configuration.",
|
||||
)
|
||||
)
|
||||
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")
|
||||
with_gripper_condition = LaunchConfiguration("with_gripper")
|
||||
initial_joint_controller = LaunchConfiguration("initial_joint_controller")
|
||||
|
||||
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",
|
||||
executable="ros2_control_node",
|
||||
parameters=[robot_description, initial_joint_controllers_file_path],
|
||||
output="both",
|
||||
remappings=[
|
||||
('motion_control_handle/target_frame', 'target_frame'),
|
||||
('cartesian_compliance_controller/target_frame', 'target_frame'),
|
||||
('cartesian_compliance_controller/target_wrench', 'target_wrench'),
|
||||
('cartesian_compliance_controller/ft_sensor_wrench', 'ft_sensor_wrench'),
|
||||
]
|
||||
)
|
||||
|
||||
joint_state_broadcaster_spawner = Node(
|
||||
package="controller_manager",
|
||||
executable="spawner",
|
||||
arguments=["joint_state_broadcaster", "-c", "/controller_manager"],
|
||||
)
|
||||
|
||||
# FIXME: Start controllers one controller by one launch or launch it all and switch by runtime?
|
||||
initial_joint_controller_spawner_started = Node(
|
||||
package="controller_manager",
|
||||
executable="spawner",
|
||||
arguments=[initial_joint_controller, "-c", "/controller_manager"],
|
||||
condition=IfCondition(start_joint_controller),
|
||||
)
|
||||
initial_joint_controller_spawner_stopped = Node(
|
||||
package="controller_manager",
|
||||
executable="spawner",
|
||||
arguments=[initial_joint_controller, "-c", "/controller_manager", "--inactive"],
|
||||
condition=UnlessCondition(start_joint_controller),
|
||||
)
|
||||
|
||||
gripper_controller = ExecuteProcess(
|
||||
cmd=['ros2', 'control', 'load_controller', '--set-state', 'active',
|
||||
"gripper_controller"],
|
||||
output='screen',
|
||||
condition=IfCondition(with_gripper_condition)
|
||||
)
|
||||
cartesian_motion_controller_spawner = Node(
|
||||
package="controller_manager",
|
||||
executable="spawner",
|
||||
arguments=["cartesian_motion_controller", "--inactive", "-c", "/controller_manager"],
|
||||
)
|
||||
motion_control_handle_spawner = Node(
|
||||
package="controller_manager",
|
||||
executable="spawner",
|
||||
arguments=["motion_control_handle", "--inactive", "-c", "/controller_manager"],
|
||||
)
|
||||
|
||||
cartesian_compliance_controller_spawner = Node(
|
||||
package="controller_manager",
|
||||
executable="spawner",
|
||||
arguments=["cartesian_compliance_controller", "--inactive", "-c", "/controller_manager"],
|
||||
)
|
||||
|
||||
nodes_to_start = [
|
||||
control_node,
|
||||
joint_state_broadcaster_spawner,
|
||||
initial_joint_controller_spawner_started,
|
||||
initial_joint_controller_spawner_stopped,
|
||||
gripper_controller,
|
||||
cartesian_motion_controller_spawner,
|
||||
motion_control_handle_spawner,
|
||||
cartesian_compliance_controller_spawner
|
||||
]
|
||||
|
||||
return LaunchDescription(declared_arguments + nodes_to_start)
|
|
@ -1,198 +0,0 @@
|
|||
import os
|
||||
from launch_ros.actions import Node
|
||||
from launch import LaunchDescription
|
||||
from launch.actions import DeclareLaunchArgument
|
||||
from launch_ros.substitutions import FindPackageShare
|
||||
from launch.substitutions import Command, FindExecutable, LaunchConfiguration, PathJoinSubstitution
|
||||
from launch.conditions import IfCondition
|
||||
from ur_moveit_config.launch_common import load_yaml
|
||||
|
||||
|
||||
|
||||
|
||||
def generate_launch_description():
|
||||
declared_arguments = []
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument(
|
||||
"robot_description",
|
||||
default_value="",
|
||||
description="robot description string",
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument(
|
||||
"robot_description_semantic",
|
||||
default_value="",
|
||||
description="robot description semantic string",
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument(
|
||||
"moveit_config_package",
|
||||
default_value="ur_moveit_config",
|
||||
description="MoveIt config package with robot SRDF/XACRO files. Usually the argument \
|
||||
is not set, it enables use of a custom moveit config.",
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument(
|
||||
"moveit_config_file",
|
||||
default_value="ur.srdf.xacro",
|
||||
description="MoveIt SRDF/XACRO description file with the robot.",
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument(
|
||||
"use_sim_time",
|
||||
default_value="true",
|
||||
description="Make MoveIt to use simulation time. This is needed for the trajectory planing in simulation.",
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument(
|
||||
"prefix",
|
||||
default_value='""',
|
||||
description="Prefix of the joint names, useful for \
|
||||
multi-robot setup. If changed than also joint names in the controllers' configuration \
|
||||
have to be updated.",
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument(
|
||||
"with_gripper",
|
||||
default_value="false",
|
||||
description="With gripper or not?",
|
||||
)
|
||||
)
|
||||
|
||||
prefix = LaunchConfiguration("prefix")
|
||||
moveit_config_package = LaunchConfiguration("moveit_config_package")
|
||||
moveit_config_file = LaunchConfiguration("moveit_config_file")
|
||||
use_sim_time = LaunchConfiguration("use_sim_time")
|
||||
with_gripper_condition = LaunchConfiguration("with_gripper")
|
||||
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}
|
||||
|
||||
world_config_file = PathJoinSubstitution(
|
||||
[FindPackageShare("rbs_simulation"), "worlds", "mir.sdf"]
|
||||
)
|
||||
|
||||
robot_description_kinematics = PathJoinSubstitution(
|
||||
[FindPackageShare(moveit_config_package), "config", "kinematics.yaml"]
|
||||
)
|
||||
|
||||
# Planning Configuration
|
||||
ompl_planning_pipeline_config = {
|
||||
"move_group": {
|
||||
"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_yaml = load_yaml("ur_moveit_config", "config/ompl_planning.yaml")
|
||||
ompl_planning_pipeline_config["move_group"].update(ompl_planning_yaml)
|
||||
|
||||
controllers_yaml = load_yaml("ur_moveit_config", "config/controllers.yaml")
|
||||
|
||||
moveit_controllers = {
|
||||
"moveit_simple_controller_manager": controllers_yaml,
|
||||
"moveit_controller_manager": "moveit_simple_controller_manager/MoveItSimpleControllerManager",
|
||||
}
|
||||
|
||||
trajectory_execution = {
|
||||
"moveit_manage_controllers": True,
|
||||
"trajectory_execution.allowed_execution_duration_scaling": 100.0,
|
||||
"trajectory_execution.allowed_goal_duration_margin": 0.5,
|
||||
"trajectory_execution.allowed_start_tolerance": 0.01,
|
||||
}
|
||||
|
||||
planning_scene_monitor_parameters = {
|
||||
"publish_planning_scene": True,
|
||||
"publish_geometry_updates": True,
|
||||
"publish_state_updates": True,
|
||||
"publish_transforms_updates": True,
|
||||
}
|
||||
|
||||
move_group_node = Node(
|
||||
package="moveit_ros_move_group",
|
||||
executable="move_group",
|
||||
output="screen",
|
||||
parameters=[
|
||||
robot_description,
|
||||
robot_description_semantic,
|
||||
robot_description_kinematics,
|
||||
ompl_planning_pipeline_config,
|
||||
trajectory_execution,
|
||||
moveit_controllers,
|
||||
planning_scene_monitor_parameters,
|
||||
use_sim_time,
|
||||
],
|
||||
)
|
||||
|
||||
move_topose_action_server = Node(
|
||||
package="rbs_skill_servers",
|
||||
executable="move_topose_action_server",
|
||||
parameters=[
|
||||
robot_description,
|
||||
robot_description_semantic,
|
||||
robot_description_kinematics,
|
||||
use_sim_time,
|
||||
]
|
||||
)
|
||||
|
||||
gripper_control_node = Node(
|
||||
package="rbs_skill_servers",
|
||||
executable="gripper_control_action_server",
|
||||
parameters= [
|
||||
robot_description,
|
||||
robot_description_semantic,
|
||||
robot_description_kinematics,
|
||||
use_sim_time,
|
||||
],
|
||||
condition=IfCondition(with_gripper_condition)
|
||||
)
|
||||
|
||||
move_cartesian_path_action_server = Node(
|
||||
package="rbs_skill_servers",
|
||||
executable="move_cartesian_path_action_server",
|
||||
parameters=[
|
||||
robot_description,
|
||||
robot_description_semantic,
|
||||
robot_description_kinematics,
|
||||
use_sim_time,
|
||||
]
|
||||
)
|
||||
|
||||
move_joint_state_action_server = Node(
|
||||
package="rbs_skill_servers",
|
||||
executable="move_to_joint_states_action_server",
|
||||
parameters=[
|
||||
robot_description,
|
||||
robot_description_semantic,
|
||||
robot_description_kinematics,
|
||||
use_sim_time,
|
||||
]
|
||||
)
|
||||
|
||||
moveit_planning_scene_init = Node(
|
||||
package="rbs_skill_servers",
|
||||
executable="moveit_update_planning_scene_service_server",
|
||||
output="screen",
|
||||
parameters=[
|
||||
{'init_scene': world_config_file},
|
||||
{'models_paths': os.environ['IGN_GAZEBO_RESOURCE_PATH']}
|
||||
]
|
||||
)
|
||||
nodes_to_start = [
|
||||
move_group_node,
|
||||
move_topose_action_server,
|
||||
gripper_control_node,
|
||||
move_cartesian_path_action_server,
|
||||
move_joint_state_action_server,
|
||||
moveit_planning_scene_init
|
||||
]
|
||||
return LaunchDescription(declared_arguments + nodes_to_start)
|
|
@ -1,27 +0,0 @@
|
|||
from launch_ros.actions import Node
|
||||
from ur_moveit_config.launch_common import load_yaml
|
||||
from launch import LaunchDescription
|
||||
|
||||
def generate_launch_description():
|
||||
declared_arguments = []
|
||||
|
||||
points_params = load_yaml("rbs_bt_executor", "config/gripperPositions.yaml")
|
||||
|
||||
grasp_pose_loader = Node(
|
||||
package="rbs_skill_servers",
|
||||
executable="pick_place_pose_loader_service_server",
|
||||
output="screen",
|
||||
emulate_tty=True,
|
||||
parameters=[
|
||||
points_params
|
||||
]
|
||||
)
|
||||
grasp_marker = Node(
|
||||
package="rbs_perception",
|
||||
executable="grasp_marker_publish.py",
|
||||
)
|
||||
nodes_to_start = [
|
||||
grasp_pose_loader,
|
||||
grasp_marker
|
||||
]
|
||||
return LaunchDescription(declared_arguments + nodes_to_start)
|
|
@ -1,65 +0,0 @@
|
|||
import os
|
||||
from launch_ros.actions import Node
|
||||
from launch import LaunchDescription
|
||||
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
|
||||
from launch_ros.substitutions import FindPackageShare
|
||||
from launch.substitutions import Command, FindExecutable, LaunchConfiguration, PathJoinSubstitution
|
||||
from launch.conditions import IfCondition
|
||||
from launch.launch_description_sources import PythonLaunchDescriptionSource
|
||||
from ament_index_python.packages import get_package_share_directory
|
||||
|
||||
|
||||
def generate_launch_description():
|
||||
declared_arguments = []
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument("sim_gazebo", default_value="false", description="Gazebo Simulation")
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument(
|
||||
"rbs_robot_type",
|
||||
description="Type of robot by name",
|
||||
choices=["ur3", "ur3e", "ur5", "ur5e", "ur10", "ur10e", "ur16e"],
|
||||
default_value="ur5e",
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument("env_manager", default_value="false", description="Launch env_manager?")
|
||||
)
|
||||
|
||||
sim_gazebo = LaunchConfiguration("sim_gazebo")
|
||||
rbs_robot_type = LaunchConfiguration("rbs_robot_type")
|
||||
env_manager_cond = LaunchConfiguration("env_manager")
|
||||
|
||||
# FIXME: To args when we'll have different files
|
||||
world_config_file = PathJoinSubstitution(
|
||||
[FindPackageShare("rbs_simulation"), "worlds", "mir.sdf"]
|
||||
)
|
||||
# Gazebo nodes
|
||||
gazebo = IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource(
|
||||
[os.path.join(get_package_share_directory('ros_ign_gazebo'),
|
||||
'launch', 'ign_gazebo.launch.py')]),
|
||||
launch_arguments=[('ign_args', [' -r ',world_config_file, " --physics-engine ignition-physics-dartsim-plugin --render-engine ogre2"])],
|
||||
condition=IfCondition(sim_gazebo))
|
||||
# Spawn robot
|
||||
gazebo_spawn_robot = Node(package='ros_ign_gazebo', executable='create',
|
||||
arguments=[
|
||||
'-name', rbs_robot_type,
|
||||
'-x', '0.0',
|
||||
'-z', '0.0',
|
||||
'-y', '0.0',
|
||||
'-topic', '/robot_description'],
|
||||
output='screen',
|
||||
condition=IfCondition(sim_gazebo))
|
||||
|
||||
env_manager = Node(package="env_manager",
|
||||
executable="env_manager_node",
|
||||
condition=IfCondition(env_manager_cond)
|
||||
)
|
||||
|
||||
nodes_to_start = [
|
||||
gazebo,
|
||||
gazebo_spawn_robot,
|
||||
env_manager
|
||||
]
|
||||
return LaunchDescription(declared_arguments + nodes_to_start)
|
Loading…
Add table
Add a link
Reference in a new issue