Skip to content
Open
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
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,4 @@ def generate_launch_description():
launch_arguments={'world_name': world_file}.items(),
)

return LaunchDescription(
[SetParameter(name='use_sim_time', value=True), world_launch]
)
return LaunchDescription([SetParameter(name='use_sim_time', value=True), world_launch])
31 changes: 14 additions & 17 deletions raspimouse_gazebo/launch/raspimouse_with_emptyworld.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -56,8 +56,7 @@ def generate_launch_description():
)
declare_arg_world_name = DeclareLaunchArgument(
'world_name',
default_value=get_package_share_directory('raspimouse_gazebo')
+ '/worlds/empty_world.sdf',
default_value=get_package_share_directory('raspimouse_gazebo') + '/worlds/empty_world.sdf',
description='Set world name.',
)
declare_arg_spawn_x = DeclareLaunchArgument(
Expand Down Expand Up @@ -120,9 +119,7 @@ def generate_launch_description():
description_loader.use_rgb_camera = LaunchConfiguration('use_rgb_camera')
description_loader.camera_downward = LaunchConfiguration('camera_downward')
description_loader.gz_control_config_package = 'raspimouse_gazebo'
description_loader.gz_control_config_file_path = (
'config/raspimouse_controllers.yaml'
)
description_loader.gz_control_config_file_path = 'config/raspimouse_controllers.yaml'

robot_state_publisher = Node(
package='robot_state_publisher',
Expand All @@ -131,54 +128,54 @@ def generate_launch_description():
parameters=[{'robot_description': description_loader.load()}],
)

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

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

rviz_config_file = (
get_package_share_directory('raspimouse_gazebo') + '/config/config.rviz'
)
rviz_config_file = get_package_share_directory('raspimouse_gazebo') + '/config/config.rviz'
rviz = Node(
name='rviz2',
package='rviz2',
executable='rviz2',
name='rviz2',
output='screen',
arguments=['-d', rviz_config_file],
)

bridge = Node(
package='ros_gz_bridge',
executable='parameter_bridge',
output='screen',
arguments=[
'/clock@rosgraph_msgs/msg/Clock[gz.msgs.Clock',
'/scan@sensor_msgs/msg/[email protected]',
'/camera/color/image_raw@sensor_msgs/msg/[email protected]',
'/camera_info@sensor_msgs/msg/[email protected]',
],
output='screen',
)

container = ComposableNodeContainer(
name='fake_raspimouse_container',
namespace='',
package='rclcpp_components',
executable='component_container_mt',
output='screen',
composable_node_descriptions=[
ComposableNode(
package='raspimouse_fake',
plugin='fake_raspimouse::Raspimouse',
name='raspimouse',
),
],
output='screen',
)

return LaunchDescription(
Expand Down
4 changes: 1 addition & 3 deletions raspimouse_gazebo/launch/raspimouse_with_lakehouse.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,4 @@ def generate_launch_description():
launch_arguments={'world_name': world_file}.items(),
)

return LaunchDescription(
[SetParameter(name='use_sim_time', value=True), world_launch]
)
return LaunchDescription([SetParameter(name='use_sim_time', value=True), world_launch])
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,4 @@ def generate_launch_description():
}.items(),
)

return LaunchDescription(
[SetParameter(name='use_sim_time', value=True), world_launch]
)
return LaunchDescription([SetParameter(name='use_sim_time', value=True), world_launch])