Skip to content
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
138 changes: 72 additions & 66 deletions sciurus17_control/launch/sciurus17_control.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,17 +17,14 @@
from ament_index_python.packages import get_package_share_directory
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
from sciurus17_description.robot_description_loader import RobotDescriptionLoader


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

description_loader = RobotDescriptionLoader()
Expand All @@ -40,73 +37,82 @@ def generate_launch_description():
'loaded_description',
default_value=description_loader.load(),
description='Set robot_description text. \
It is recommended to use RobotDescriptionLoader() in sciurus17_description.'
It is recommended to use RobotDescriptionLoader() in sciurus17_description.',
)

sciurus17_controllers = os.path.join(
get_package_share_directory('sciurus17_control'),
'config',
'sciurus17_controllers.yaml'
)
get_package_share_directory('sciurus17_control'), 'config', 'sciurus17_controllers.yaml'
)

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

spawn_joint_state_broadcaster = ExecuteProcess(
cmd=['ros2 run controller_manager spawner joint_state_broadcaster'],
shell=True,
output='screen',
)

spawn_right_arm_controller = ExecuteProcess(
cmd=['ros2 run controller_manager spawner right_arm_controller'],
shell=True,
output='screen',
)

spawn_right_gripper_controller = ExecuteProcess(
cmd=['ros2 run controller_manager spawner right_gripper_controller'],
shell=True,
output='screen',
)

spawn_left_arm_controller = ExecuteProcess(
cmd=['ros2 run controller_manager spawner left_arm_controller'],
shell=True,
output='screen',
)

spawn_left_gripper_controller = ExecuteProcess(
cmd=['ros2 run controller_manager spawner left_gripper_controller'],
shell=True,
output='screen',
)

spawn_neck_controller = ExecuteProcess(
cmd=['ros2 run controller_manager spawner neck_controller'],
shell=True,
output='screen',
)

spawn_waist_yaw_controller = ExecuteProcess(
cmd=['ros2 run controller_manager spawner waist_yaw_controller'],
shell=True,
output='screen',
)

return LaunchDescription([
declare_loaded_description,
controller_manager,
spawn_right_arm_controller,
spawn_right_gripper_controller,
spawn_left_arm_controller,
spawn_left_gripper_controller,
spawn_joint_state_broadcaster,
spawn_neck_controller,
spawn_waist_yaw_controller
])
parameters=[
{'robot_description': LaunchConfiguration('loaded_description')},
sciurus17_controllers,
],
)

spawn_joint_state_broadcaster = Node(
package='controller_manager',
executable='spawner',
output='screen',
arguments=['joint_state_broadcaster'],
)

spawn_right_arm_controller = Node(
package='controller_manager',
executable='spawner',
output='screen',
arguments=['right_arm_controller'],
)

spawn_right_gripper_controller = Node(
package='controller_manager',
executable='spawner',
output='screen',
arguments=['right_gripper_controller'],
)

spawn_left_arm_controller = Node(
package='controller_manager',
executable='spawner',
output='screen',
arguments=['left_arm_controller'],
)

spawn_left_gripper_controller = Node(
package='controller_manager',
executable='spawner',
output='screen',
arguments=['left_gripper_controller'],
)

spawn_neck_controller = Node(
package='controller_manager',
executable='spawner',
output='screen',
arguments=['neck_controller'],
)

spawn_waist_yaw_controller = Node(
package='controller_manager',
executable='spawner',
output='screen',
arguments=['waist_yaw_controller'],
)

return LaunchDescription(
[
declare_loaded_description,
controller_manager,
spawn_right_arm_controller,
spawn_right_gripper_controller,
spawn_left_arm_controller,
spawn_left_gripper_controller,
spawn_joint_state_broadcaster,
spawn_neck_controller,
spawn_waist_yaw_controller,
]
)
94 changes: 36 additions & 58 deletions sciurus17_examples/launch/camera_example.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,78 +12,56 @@
# 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 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
from moveit_configs_utils import MoveItConfigsBuilder
from sciurus17_description.robot_description_loader import RobotDescriptionLoader
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


def generate_launch_description():
description_loader = RobotDescriptionLoader()

robot_description_semantic_config = load_file(
'sciurus17_moveit_config', 'config/sciurus17.srdf')
robot_description_semantic = {
'robot_description_semantic': robot_description_semantic_config}

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

declare_example_name = DeclareLaunchArgument(
'example', default_value='point_cloud_detection',
description=('Set an example executable name: '
'[point_cloud_detection]')
'example',
default_value='point_cloud_detection',
description=('Set an example executable name: [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='sciurus17_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('sciurus17').to_moveit_configs()
moveit_config.robot_description = {
'robot_description': description_loader.load(),
}

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

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

return LaunchDescription([
declare_use_sim_time,
SetParameter(name='use_sim_time', value=LaunchConfiguration('use_sim_time')),
picking_node,
declare_example_name,
detection_node
])
return LaunchDescription(
[
declare_example_name,
declare_use_sim_time,
SetParameter(name='use_sim_time', value=LaunchConfiguration('use_sim_time')),
picking_node,
detection_node,
]
)
51 changes: 25 additions & 26 deletions sciurus17_examples/launch/chest_camera_tracking.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -22,49 +22,48 @@

def generate_launch_description():
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.'),
)

container = ComposableNodeContainer(
name='tracking_container',
namespace='head_camera_tracking',
package='rclcpp_components',
executable='component_container',
output='screen',
composable_node_descriptions=[
ComposableNode(
package='sciurus17_examples',
plugin='sciurus17_examples::ColorDetection',
name='color_detection',
namespace='chest_camera_tracking',
remappings=[
('/image_raw', '/chest_camera/image_raw')
],
extra_arguments=[{'use_intra_process_comms': True}]
),
ComposableNode(
package='sciurus17_examples',
plugin='sciurus17_examples::ObjectTracker',
plugin='sciurus17_examples::ColorDetection',
remappings=[('/image_raw', '/chest_camera/image_raw')],
extra_arguments=[{'use_intra_process_comms': True}],
),
ComposableNode(
name='object_tracker',
namespace='chest_camera_tracking',
remappings=[
('/controller_state', '/waist_yaw_controller/controller_state')
],
extra_arguments=[{'use_intra_process_comms': True}]
),
ComposableNode(
package='sciurus17_examples',
plugin='sciurus17_examples::WaistJtControl',
plugin='sciurus17_examples::ObjectTracker',
remappings=[('/controller_state', '/waist_yaw_controller/controller_state')],
extra_arguments=[{'use_intra_process_comms': True}],
),
ComposableNode(
name='waist_jt_control',
namespace='chest_camera_tracking',
extra_arguments=[{'use_intra_process_comms': True}]
),
package='sciurus17_examples',
plugin='sciurus17_examples::WaistJtControl',
extra_arguments=[{'use_intra_process_comms': True}],
),
],
output='screen',
)

return LaunchDescription([
declare_use_sim_time,
SetParameter(name='use_sim_time', value=LaunchConfiguration('use_sim_time')),
container
])
return LaunchDescription(
[
declare_use_sim_time,
SetParameter(name='use_sim_time', value=LaunchConfiguration('use_sim_time')),
container,
]
)
Loading