Skip to content
74 changes: 37 additions & 37 deletions crane_x7_control/launch/crane_x7_control.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,22 +18,17 @@
from crane_x7_description.robot_description_loader import RobotDescriptionLoader
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.actions import ExecuteProcess
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node


def generate_launch_description():
config_file_path = os.path.join(
get_package_share_directory('crane_x7_control'),
'config',
'manipulator_config.yaml'
get_package_share_directory('crane_x7_control'), 'config', 'manipulator_config.yaml'
)

links_file_path = os.path.join(
get_package_share_directory('crane_x7_control'),
'config',
'manipulator_links.csv'
get_package_share_directory('crane_x7_control'), 'config', 'manipulator_links.csv'
)

description_loader = RobotDescriptionLoader()
Expand All @@ -47,45 +42,50 @@ def generate_launch_description():
'loaded_description',
default_value=description_loader.load(),
description='Set robot_description text. \
It is recommended to use RobotDescriptionLoader() in crane_x7_description.'
It is recommended to use RobotDescriptionLoader() in crane_x7_description.',
)

crane_x7_controllers = os.path.join(
get_package_share_directory('crane_x7_control'),
'config',
'crane_x7_controllers.yaml'
)
get_package_share_directory('crane_x7_control'), 'config', 'crane_x7_controllers.yaml'
)

controller_manager = Node(
package='controller_manager',
executable='ros2_control_node',
parameters=[{'robot_description': LaunchConfiguration('loaded_description')},
crane_x7_controllers],
output='screen',
)
parameters=[
{'robot_description': LaunchConfiguration('loaded_description')},
crane_x7_controllers,
],
)

spawn_joint_state_controller = ExecuteProcess(
cmd=['ros2 run controller_manager spawner joint_state_controller'],
shell=True,
output='screen',
)
spawn_joint_state_controller = Node(
package='controller_manager',
executable='spawner',
output='screen',
arguments=['joint_state_controller'],
)

spawn_arm_controller = ExecuteProcess(
cmd=['ros2 run controller_manager spawner crane_x7_arm_controller'],
shell=True,
output='screen',
)
spawn_arm_controller = Node(
package='controller_manager',
executable='spawner',
output='screen',
arguments=['crane_x7_arm_controller'],
)

spawn_gripper_controller = ExecuteProcess(
cmd=['ros2 run controller_manager spawner crane_x7_gripper_controller'],
shell=True,
output='screen',
)
spawn_gripper_controller = Node(
package='controller_manager',
executable='spawner',
output='screen',
arguments=['crane_x7_gripper_controller'],
)

return LaunchDescription([
declare_loaded_description,
controller_manager,
spawn_joint_state_controller,
spawn_arm_controller,
spawn_gripper_controller
])
return LaunchDescription(
[
declare_loaded_description,
controller_manager,
spawn_joint_state_controller,
spawn_arm_controller,
spawn_gripper_controller,
]
)
97 changes: 39 additions & 58 deletions crane_x7_examples/launch/camera_example.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,78 +12,59 @@
# See the License for the specific language governing permissions and
# limitations under the License.

import os

from ament_index_python.packages import get_package_share_directory
from crane_x7_description.robot_description_loader import RobotDescriptionLoader
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node
from launch_ros.actions import SetParameter
import yaml


def load_file(package_name, file_path):
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 file:
return file.read()
except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available
return None


def load_yaml(package_name, file_path):
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 file:
return yaml.safe_load(file)
except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available
return None
from moveit_configs_utils import MoveItConfigsBuilder


def generate_launch_description():
description_loader = RobotDescriptionLoader()

robot_description_semantic_config = load_file(
'crane_x7_moveit_config', 'config/crane_x7.srdf')
robot_description_semantic = {
'robot_description_semantic': robot_description_semantic_config}

kinematics_yaml = load_yaml('crane_x7_moveit_config', 'config/kinematics.yaml')

declare_example_name = DeclareLaunchArgument(
'example', default_value='color_detection',
description=('Set an example executable name: '
'[color_detection, aruco_detection, point_cloud_detection]')
'example',
default_value='color_detection',
description=(
'Set an example executable name: '
'[color_detection, aruco_detection, point_cloud_detection]'
),
)

declare_use_sim_time = DeclareLaunchArgument(
'use_sim_time', default_value='false',
description=('Set true when using the gazebo simulator.')
'use_sim_time',
default_value='false',
description=('Set true when using the gazebo simulator.'),
)

picking_node = Node(name='pick_and_place_tf',
package='crane_x7_examples',
executable='pick_and_place_tf',
output='screen',
parameters=[{'robot_description': description_loader.load()},
robot_description_semantic,
kinematics_yaml])
description_loader = RobotDescriptionLoader()

moveit_config = MoveItConfigsBuilder('crane_x7').to_moveit_configs()
moveit_config.robot_description = {
'robot_description': description_loader.load(),
}

picking_node = Node(
name='pick_and_place_tf',
package='crane_x7_examples',
executable='pick_and_place_tf',
output='screen',
parameters=[moveit_config.to_dict()],
)

detection_node = Node(name=[LaunchConfiguration('example'), '_node'],
package='crane_x7_examples',
executable=LaunchConfiguration('example'),
output='screen')
detection_node = Node(
name=[LaunchConfiguration('example'), '_node'],
package='crane_x7_examples',
executable=LaunchConfiguration('example'),
output='screen',
)

return LaunchDescription([
declare_use_sim_time,
SetParameter(name='use_sim_time', value=LaunchConfiguration('use_sim_time')),
picking_node,
detection_node,
declare_example_name
])
return LaunchDescription(
[
declare_use_sim_time,
SetParameter(name='use_sim_time', value=LaunchConfiguration('use_sim_time')),
picking_node,
detection_node,
declare_example_name,
]
)
109 changes: 50 additions & 59 deletions crane_x7_examples/launch/demo.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -27,55 +27,41 @@

def generate_launch_description():
declare_port_name = DeclareLaunchArgument(
'port_name',
default_value='/dev/ttyUSB0',
description='Set port name.'
'port_name', default_value='/dev/ttyUSB0', description='Set port name.'
)

declare_baudrate = DeclareLaunchArgument(
'baudrate',
default_value='3000000',
description='Set baudrate.'
'baudrate', default_value='3000000', description='Set baudrate.'
)

declare_use_d435 = DeclareLaunchArgument(
'use_d435',
default_value='false',
description='Use d435.'
'use_d435', default_value='false', description='Use d435.'
)

declare_use_mock_components = DeclareLaunchArgument(
'use_mock_components',
default_value='false',
description='Use mock_components or not.'
'use_mock_components', default_value='false', description='Use mock_components or not.'
)

config_file_path = os.path.join(
get_package_share_directory('crane_x7_control'),
'config',
'manipulator_config.yaml'
get_package_share_directory('crane_x7_control'), 'config', 'manipulator_config.yaml'
)

links_file_path = os.path.join(
get_package_share_directory('crane_x7_control'),
'config',
'manipulator_links.csv'
get_package_share_directory('crane_x7_control'), 'config', 'manipulator_links.csv'
)

declare_rviz_config = DeclareLaunchArgument(
'rviz_config',
default_value=get_package_share_directory(
'crane_x7_moveit_config'
) + '/config/moveit.rviz',
default_value=get_package_share_directory('crane_x7_moveit_config')
+ '/config/moveit.rviz',
description='Set the path to rviz configuration file.',
condition=UnlessCondition(LaunchConfiguration('use_d435')),
)

declare_rviz_config_camera = DeclareLaunchArgument(
'rviz_config',
default_value=get_package_share_directory(
'crane_x7_examples'
) + '/launch/camera_example.rviz',
default_value=get_package_share_directory('crane_x7_examples')
+ '/launch/camera_example.rviz',
description='Set the path to rviz configuration file.',
condition=IfCondition(LaunchConfiguration('use_d435')),
)
Expand All @@ -92,43 +78,48 @@ def generate_launch_description():
description = description_loader.load()

move_group = IncludeLaunchDescription(
PythonLaunchDescriptionSource([
PythonLaunchDescriptionSource(
[
get_package_share_directory('crane_x7_moveit_config'),
'/launch/run_move_group.launch.py']),
launch_arguments={
'loaded_description': description,
'rviz_config': LaunchConfiguration('rviz_config')
}.items()
)
'/launch/run_move_group.launch.py',
]
),
launch_arguments={
'loaded_description': description,
'rviz_config': LaunchConfiguration('rviz_config'),
}.items(),
)

control_node = IncludeLaunchDescription(
PythonLaunchDescriptionSource([
get_package_share_directory('crane_x7_control'),
'/launch/crane_x7_control.launch.py']),
launch_arguments={'loaded_description': description}.items()
)
PythonLaunchDescriptionSource(
[get_package_share_directory('crane_x7_control'), '/launch/crane_x7_control.launch.py']
),
launch_arguments={'loaded_description': description}.items(),
)

realsense_node = IncludeLaunchDescription(
PythonLaunchDescriptionSource([
get_package_share_directory('realsense2_camera'),
'/launch/rs_launch.py']),
condition=IfCondition(LaunchConfiguration('use_d435')),
launch_arguments={
'camera_namespace': '',
'device_type': 'd435',
'pointcloud.enable': 'true',
'align_depth.enable': 'true',
}.items()
)

return LaunchDescription([
declare_port_name,
declare_baudrate,
declare_use_d435,
declare_use_mock_components,
declare_rviz_config,
declare_rviz_config_camera,
move_group,
control_node,
realsense_node
])
PythonLaunchDescriptionSource(
[get_package_share_directory('realsense2_camera'), '/launch/rs_launch.py']
),
condition=IfCondition(LaunchConfiguration('use_d435')),
launch_arguments={
'camera_namespace': '',
'device_type': 'd435',
'pointcloud.enable': 'true',
'align_depth.enable': 'true',
}.items(),
)

return LaunchDescription(
[
declare_port_name,
declare_baudrate,
declare_use_d435,
declare_use_mock_components,
declare_rviz_config,
declare_rviz_config_camera,
move_group,
control_node,
realsense_node,
]
)
Loading