Added "support" for controller plugin, currently segfaults.

This commit is contained in:
Bastian Hofmann 2023-01-24 15:19:00 +00:00
parent 3199b400d1
commit e0e44b1ffa
13 changed files with 409 additions and 142 deletions

View File

@ -1,4 +1,4 @@
#!/bin/bash #!/bin/bash
pushd "$(dirname "$0")" pushd "$(dirname "$0")" || exit
colcon build --event-handlers console_cohesion+ --cmake-args -DCMAKE_EXPORT_COMPILE_COMMANDS=ON -G Ninja colcon build --event-handlers console_cohesion+ --cmake-args -DCMAKE_EXPORT_COMPILE_COMMANDS=ON -G Ninja
popd popd || exit

View File

@ -8,54 +8,58 @@ from launch.substitutions import Command, LaunchConfiguration
from launch.launch_description_sources import PythonLaunchDescriptionSource from launch.launch_description_sources import PythonLaunchDescriptionSource
from ament_index_python.packages import get_package_share_directory from ament_index_python.packages import get_package_share_directory
def load_file(package_name, file_path): def load_file(package_name, file_path):
package_path = get_package_share_directory(package_name) package_path = get_package_share_directory(package_name)
absolute_file_path = os.path.join(package_path, file_path) absolute_file_path = os.path.join(package_path, file_path)
try: try:
with open(absolute_file_path, 'r') as file: with open(absolute_file_path, 'r') as file:
print("Opened file")
return file.read() return file.read()
except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available
print("ERROR: load_file "+package_name+"|"+file_path) print("ERROR: load_file " + package_name + " | " + file_path + " -> " + absolute_file_path)
return None return None
def load_yaml(package_name, file_path): def load_yaml(package_name, file_path):
package_path = get_package_share_directory(package_name) package_path = get_package_share_directory(package_name)
absolute_file_path = os.path.join(package_path, file_path) absolute_file_path = os.path.join(package_path, file_path)
try: try:
with open(absolute_file_path, 'r') as file: with open(absolute_file_path, 'r') as file:
print("Opened file")
return yaml.safe_load(file) return yaml.safe_load(file)
except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available
print("ERROR: load_file "+package_name+"|"+file_path) print("ERROR: load_yaml " + package_name + " | " + file_path + " -> " + absolute_file_path)
return None return None
def generate_launch_description(): def generate_launch_description():
robot_name = "iisy" robot_name = "iisy"
package_name = "gaz_simulation" # pkg_gazebo_ros = FindPackageShare(package='gazebo_ros').find('gazebo_ros')
pkg_gazebo_ros = FindPackageShare(package='gazebo_ros').find('gazebo_ros') world_path = os.path.join(FindPackageShare(package="gaz_simulation").find("gaz_simulation"), "world/test2.xml")
path = FindPackageShare(package=package_name).find(package_name) urdf_path = os.path.join(FindPackageShare(package="iisy_config").find("iisy_config"), "urdf/iisy.urdf")
world_path = os.path.join(path, "world/test2.xml")
urdf_path = os.path.join(path, "urdf/iisy.urdf")
robot_description_config = load_file('gaz_simulation', 'urdf/iisy.urdf') robot_description_config = load_file('iisy_config', 'urdf/iisy.urdf')
robot_description = {'robot_description' : robot_description_config} robot_description = {'robot_description': robot_description_config}
robot_description_semantic_config = load_file('iisy_config', 'config/iisy.srdf') robot_description_semantic_config = load_file('iisy_config', 'srdf/iisy.srdf')
robot_description_semantic = {'robot_description_semantic' : robot_description_semantic_config} robot_description_semantic = {'robot_description_semantic': robot_description_semantic_config}
kinematics_yaml = load_yaml('iisy_config', 'config/kinematics.yaml') kinematics_yaml = load_yaml('iisy_config', 'config/kinematics.yml')
robot_description_kinematics = { 'robot_description_kinematics' : kinematics_yaml } robot_description_kinematics = {'robot_description_kinematics': kinematics_yaml}
ompl_planning_pipeline_config = { 'move_group' : { ompl_planning_pipeline_config = {'move_group': {
'planning_plugin' : 'ompl_interface/OMPLPlanner', '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""" , '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 } } 'start_state_max_bounds_error': 0.1}}
ompl_planning_yaml = load_yaml('iisy_config', 'config/ompl_planning.yaml') ompl_planning_yaml = load_yaml('iisy_config', 'config/ompl_planning.yml')
ompl_planning_pipeline_config['move_group'].update(ompl_planning_yaml) ompl_planning_pipeline_config['move_group'].update(ompl_planning_yaml)
controllers_yaml = load_yaml('iisy_config', 'config/gazebo_controllers.yaml') controllers_yaml = load_yaml('iisy_config', 'config/iisy_controllers.yml')
moveit_controllers = { 'moveit_simple_controller_manager' : controllers_yaml, moveit_controllers = {'moveit_simple_controller_manager': controllers_yaml,
'moveit_controller_manager': 'moveit_simple_controller_manager/MoveItSimpleControllerManager'} 'moveit_controller_manager': 'moveit_simple_controller_manager/MoveItSimpleControllerManager'}
trajectory_execution = {'moveit_manage_controllers': True, trajectory_execution = {'moveit_manage_controllers': True,
@ -68,27 +72,26 @@ def generate_launch_description():
"publish_state_updates": True, "publish_state_updates": True,
"publish_transforms_updates": True} "publish_transforms_updates": True}
# octomap_config = {'octomap_frame': 'camera_rgb_optical_frame',
#octomap_config = {'octomap_frame': 'camera_rgb_optical_frame',
# 'octomap_resolution': 0.05, # 'octomap_resolution': 0.05,
# 'max_range': 5.0} # 'max_range': 5.0}
#octomap_updater_config = load_yaml('moveit_tutorials', 'config/sensors_3d.yaml') # octomap_updater_config = load_yaml('moveit_tutorials', 'config/sensors_3d.yaml')
return LaunchDescription([ return LaunchDescription([
SetEnvironmentVariable(name='LIBGL_ALWAYS_SOFTWARE', value='true'), # SetEnvironmentVariable(name='LIBGL_ALWAYS_SOFTWARE', value='true'),
IncludeLaunchDescription( # IncludeLaunchDescription(
PythonLaunchDescriptionSource(os.path.join(pkg_gazebo_ros, 'launch', 'gzserver.launch.py')), # PythonLaunchDescriptionSource(os.path.join(pkg_gazebo_ros, 'launch', 'gzserver.launch.py')),
launch_arguments={'world': world_path}.items() # launch_arguments={'world': world_path}.items()
), # ),
UnsetEnvironmentVariable(name='LIBGL_ALWAYS_SOFTWARE'), # UnsetEnvironmentVariable(name='LIBGL_ALWAYS_SOFTWARE'),
# Start Gazebo client # Start Gazebo client
IncludeLaunchDescription( # IncludeLaunchDescription(
PythonLaunchDescriptionSource(os.path.join(pkg_gazebo_ros, 'launch', 'gzclient.launch.py')) # PythonLaunchDescriptionSource(os.path.join(pkg_gazebo_ros, 'launch', 'gzclient.launch.py'))
), # ),
Node( Node(
package='tf2_ros', package='tf2_ros',
@ -106,19 +109,19 @@ def generate_launch_description():
arguments=["-1.9", "1", "1", "0", "0", "0", "map", "lidar_2_link"] arguments=["-1.9", "1", "1", "0", "0", "0", "map", "lidar_2_link"]
), ),
Node(
package='gazebo_ros',
executable='spawn_entity.py',
arguments=['-entity', robot_name,
'-topic', 'robot_description',
'-x', '-1',
'-y', '-1',
'-z', '1',
'-Y', '0'], # Yaw
output='screen'
),
#Node( #Node(
# package='gazebo_ros',
# executable='spawn_entity.py',
# arguments=['-entity', robot_name,
# '-topic', 'robot_description',
# '-x', '-1',
# '-y', '-1',
# '-z', '1',
# '-Y', '0'], # Yaw
# output='screen'
#),
# Node(
# package="gazebo_ros", # package="gazebo_ros",
# executable="spawn_entity.py", # executable="spawn_entity.py",
# arguments=[ # arguments=[
@ -126,15 +129,15 @@ def generate_launch_description():
# "-entity", LaunchConfiguration("iisy") # "-entity", LaunchConfiguration("iisy")
# ], # ],
# output="screen" # output="screen"
#), # ),
#Node( # Node(
# package='robot_state_publisher', # package='robot_state_publisher',
# executable='robot_state_publisher', # executable='robot_state_publisher',
# name='robot_state_publisher', # name='robot_state_publisher',
# output='both', # output='both',
# parameters=[robot_description] # parameters=[robot_description]
#), # ),
Node( Node(
package='robot_state_publisher', package='robot_state_publisher',
@ -143,8 +146,8 @@ def generate_launch_description():
), ),
Node( Node(
package='joint_state_publisher', package='robot_state_publisher',
executable='joint_state_publisher', executable='robot_state_publisher',
name='joint_state_publisher' name='joint_state_publisher'
), ),
@ -168,7 +171,7 @@ def generate_launch_description():
Node(package='moveit_ros_move_group', Node(package='moveit_ros_move_group',
executable='move_group', executable='move_group',
#prefix='xterm -fs 10 -e gdb --ex run --args', # prefix='xterm -fs 10 -e gdb --ex run --args',
output='screen', output='screen',
parameters=[ parameters=[
robot_description, robot_description,
@ -178,8 +181,8 @@ def generate_launch_description():
trajectory_execution, trajectory_execution,
moveit_controllers, moveit_controllers,
planning_scene_monitor_parameters, planning_scene_monitor_parameters,
#octomap_config, # octomap_config,
#octomap_updater_config # octomap_updater_config
] ]
), ),
]) ])

1
src/gz_ros2_control Submodule

@ -0,0 +1 @@
Subproject commit b0c29c2f3245eca25753fbe2527eeacc7cb9dac0

View File

@ -1,6 +0,0 @@
string animation_name
float32 animation_speed
---
bool success
---
float32 progress

View File

@ -1,8 +0,0 @@
string animation_name
float32 animation_speed
float32[3] target_position
float32[3] target_orientation
---
bool success
---
float32 progress

View File

@ -0,0 +1,28 @@
cmake_minimum_required(VERSION 3.8)
project(ign_world)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
# find dependencies
find_package(ament_cmake REQUIRED)
# uncomment the following section in order to fill in
# further dependencies manually.
# find_package(<dependency> REQUIRED)
install(DIRECTORY launch DESTINATION share/${PROJECT_NAME})
install(DIRECTORY world DESTINATION share/${PROJECT_NAME})
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
# uncomment the line when a copyright and license is not present in all source files
#set(ament_cmake_copyright_FOUND TRUE)
# the following line skips cpplint (only works in a git repo)
# uncomment the line when this package is not in a git repo
#set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()
ament_package()

View File

@ -0,0 +1,238 @@
import os
import subprocess
import yaml
from launch import LaunchDescription
from launch_ros.actions import Node
from launch.actions import IncludeLaunchDescription, SetEnvironmentVariable, UnsetEnvironmentVariable
from launch_ros.substitutions import FindPackageShare
from launch.substitutions import Command, LaunchConfiguration
from launch.launch_description_sources import PythonLaunchDescriptionSource
from ament_index_python.packages import get_package_share_directory
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:
print("Opened file")
return file.read()
except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available
print("ERROR: load_file " + package_name + " | " + file_path + " -> " + absolute_file_path)
return None
def load_xacro(package_name, file_path):
package_path = get_package_share_directory(package_name)
absolute_file_path = os.path.join(package_path, file_path)
process = subprocess.run(["xacro", absolute_file_path], capture_output=True)
if process.returncode != 0:
print(process.stderr)
return process.stdout.decode("UTF-8")
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:
print("Opened file")
return yaml.safe_load(file)
except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available
print("ERROR: load_yaml " + package_name + " | " + file_path + " -> " + absolute_file_path)
return None
def generate_launch_description():
robot_name = "iisy"
# pkg_gazebo_ros = FindPackageShare(package='gazebo_ros').find('gazebo_ros')
world_path = os.path.join(FindPackageShare(package="gaz_simulation").find("gaz_simulation"), "world/test2.xml")
urdf_path = os.path.join(FindPackageShare(package="iisy_config").find("iisy_config"), "urdf/iisy.urdf")
robot_description_config = load_xacro('iisy_config', 'urdf/iisy.urdf')
robot_description = {'robot_description': robot_description_config}
robot_description_semantic_config = load_file('iisy_config', 'srdf/iisy.srdf')
robot_description_semantic = {'robot_description_semantic': robot_description_semantic_config}
kinematics_yaml = load_yaml('iisy_config', 'config/kinematics.yml')
robot_description_kinematics = {'robot_description_kinematics': kinematics_yaml}
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('iisy_config', 'config/ompl_planning.yml')
ompl_planning_pipeline_config['move_group'].update(ompl_planning_yaml)
controllers_yaml = load_yaml('iisy_config', 'config/iisy_moveit_controllers.yml')
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': 1.2,
'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}
planning = {
"move_group": {
"planning_plugin": "ompl_interface/OMPLPlanner",
"request_adapters": "default_planner_request_adapters/AddTimeParameterization 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
}
}
# octomap_config = {'octomap_frame': 'camera_rgb_optical_frame',
# 'octomap_resolution': 0.05,
# 'max_range': 5.0}
# octomap_updater_config = load_yaml('moveit_tutorials', 'config/sensors_3d.yaml')
return LaunchDescription([
# SetEnvironmentVariable(name='LIBGL_ALWAYS_SOFTWARE', value='true'),
# IncludeLaunchDescription(
# PythonLaunchDescriptionSource(os.path.join(pkg_gazebo_ros, 'launch', 'gzserver.launch.py')),
# launch_arguments={'world': world_path}.items()
# ),
# UnsetEnvironmentVariable(name='LIBGL_ALWAYS_SOFTWARE'),
# Start Gazebo client
# IncludeLaunchDescription(
# PythonLaunchDescriptionSource(os.path.join(pkg_gazebo_ros, 'launch', 'gzclient.launch.py'))
# ),
Node(
package='ros_gz_sim',
executable='create',
arguments=['-world', 'empty', '-string', robot_description_config],
output='screen'
),
Node(
package='tf2_ros',
namespace='gaz_simulation',
executable='static_transform_publisher',
name='lidar_1_broadcaster',
arguments=[
"--x", "1",
"--y", "-1.9",
"--z", "1",
"--roll", "1.5707963267949",
"--pitch", "0",
"--yaw", "0",
"--frame-id", "map",
"--child-frame-id", "lidar_1_link"]
),
Node(
package='tf2_ros',
namespace='gaz_simulation',
executable='static_transform_publisher',
name='lidar_2_broadcaster',
arguments=[
"--x", "-1.9",
"--y", "1",
"--z", "1",
"--roll", "0",
"--pitch", "0",
"--yaw", "0",
"--frame-id", "map",
"--child-frame-id", "lidar_2_link"]
),
# Node(
# package='gazebo_ros',
# executable='spawn_entity.py',
# arguments=['-entity', robot_name,
# '-topic', 'robot_description',
# '-x', '-1',
# '-y', '-1',
# '-z', '1',
# '-Y', '0'], # Yaw
# output='screen'
# ),
# Node(
# package="gazebo_ros",
# executable="spawn_entity.py",
# arguments=[
# "-topic", "robot_description",
# "-entity", LaunchConfiguration("iisy")
# ],
# output="screen"
# ),
# Node(
# package='robot_state_publisher',
# executable='robot_state_publisher',
# name='robot_state_publisher',
# output='both',
# parameters=[robot_description]
# ),
Node(
package='robot_state_publisher',
executable='robot_state_publisher',
parameters=[robot_description]
),
# ,
# Node(
# namespace='turtlesim1',
# executable='gazebo',
# name='gazebo',
# arguments=["test.xml"]
# )
# Node(
# package='controller_manager',
# name='gazebo_controller_spawner',
# executable='spawner',
# output='screen',
# parameters=[
# controllers_yaml,
# ]
# ),
Node(package='moveit_ros_move_group',
executable='move_group',
# prefix='xterm -fs 10 -e gdb --ex run --args',
output='screen',
parameters=[
robot_description,
robot_description_semantic,
kinematics_yaml,
ompl_planning_pipeline_config,
trajectory_execution,
moveit_controllers,
planning_scene_monitor_parameters,
# octomap_config,
# octomap_updater_config
]
),
Node(
package='rviz2',
executable='rviz2',
# arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'gpu_lidar_bridge.rviz')],
parameters=[
robot_description,
robot_description_semantic,
kinematics_yaml,
planning,
],
),
])

28
src/ign_world/package.xml Normal file
View File

@ -0,0 +1,28 @@
<package format="3">
<name>ign_world</name>
<version>0.244.1</version>
<description>Launch file for simulation of pick and place</description>
<license>Apache 2.0</license>
<maintainer email="bastian.hofmann@xitaso.com">Bastian Hofmann</maintainer>
<buildtool_depend>ament_cmake</buildtool_depend>
<exec_depend>gazebo</exec_depend>
<exec_depend>image_transport_plugins</exec_depend>
<exec_depend>robot_state_publisher</exec_depend>
<exec_depend>ros_ign_bridge</exec_depend>
<exec_depend>ros_ign_gazebo</exec_depend>
<exec_depend>ros_ign_image</exec_depend>
<!-- See https://github.com/osrf/ros_ign/issues/40 -->
<!--exec_depend>ros_ign_point_cloud</exec_depend-->
<exec_depend>rqt_image_view</exec_depend>
<exec_depend>rqt_plot</exec_depend>
<exec_depend>rqt_topic</exec_depend>
<exec_depend>rviz2</exec_depend>
<exec_depend>xacro</exec_depend>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>

View File

@ -4,22 +4,10 @@
<max_step_size>0.001</max_step_size> <max_step_size>0.001</max_step_size>
<real_time_factor>1.0</real_time_factor> <real_time_factor>1.0</real_time_factor>
</physics> </physics>
<plugin <plugin name='ignition::gazebo::systems::Physics' filename='ignition-gazebo-physics-system'/>
filename="gz-sim-physics-system" <plugin name='ignition::gazebo::systems::UserCommands' filename='ignition-gazebo-user-commands-system'/>
name="gz::sim::systems::Physics"> <plugin name='ignition::gazebo::systems::SceneBroadcaster' filename='ignition-gazebo-scene-broadcaster-system'/>
</plugin> <plugin name='ignition::gazebo::systems::Contact' filename='ignition-gazebo-contact-system'/>
<plugin
filename="gz-sim-user-commands-system"
name="gz::sim::systems::UserCommands">
</plugin>
<plugin
filename="gz-sim-scene-broadcaster-system"
name="gz::sim::systems::SceneBroadcaster">
</plugin>
<plugin
filename="gz-sim-contact-system"
name="gz::sim::systems::Contact">
</plugin>
<light type="directional" name="sun"> <light type="directional" name="sun">
<cast_shadows>true</cast_shadows> <cast_shadows>true</cast_shadows>

View File

@ -9,7 +9,7 @@ from launch.launch_description_sources import PythonLaunchDescriptionSource
def generate_launch_description(): def generate_launch_description():
package_name = "gaz_simulation" package_name = "gaz_simulation"
pkg_gazebo_ros = FindPackageShare('gazebo_ros').find('gazebo_ros') pkg_gazebo_ros = FindPackageShare('gaz_simulation').find('gaz_simulation')
path = FindPackageShare(package=package_name).find(package_name) path = FindPackageShare(package=package_name).find(package_name)
world_path = os.path.join(path, "world/test2.xml") world_path = os.path.join(path, "world/test2.xml")
@ -17,15 +17,15 @@ def generate_launch_description():
# ROS2 control demos via environment hook https://github.com/ros-controls/ros2_control_demos/tree/master/ros2_control_demo_description/rrbot_description # ROS2 control demos via environment hook https://github.com/ros-controls/ros2_control_demos/tree/master/ros2_control_demo_description/rrbot_description
# Also see https://colcon.readthedocs.io/en/released/developer/environment.html#dsv-files # Also see https://colcon.readthedocs.io/en/released/developer/environment.html#dsv-files
# Gazebo launch scripts append GAZEBO_MODEL_PATH with known paths, see https://github.com/ros-simulation/gazebo_ros_pkgs/blob/ab1ae5c05eda62674b36df74eb3be8c93cdc8761/gazebo_ros/launch/gzclient.launch.py#L26 # Gazebo launch scripts append GAZEBO_MODEL_PATH with known paths, see https://github.com/ros-simulation/gazebo_ros_pkgs/blob/ab1ae5c05eda62674b36df74eb3be8c93cdc8761/gazebo_ros/launch/gzclient.launch.py#L26
spawn_entity = Node( #spawn_entity = Node(
package="gazebo_ros", # package="gazebo_ros",
executable="spawn_entity.py", # executable="spawn_entity.py",
arguments=[ # arguments=[
"-topic", "robot_description", # "-topic", "robot_description",
"-entity", "iisy" # "-entity", "iisy"
], # ],
output="screen" # output="screen"
) #)
bringup = IncludeLaunchDescription( bringup = IncludeLaunchDescription(
PythonLaunchDescriptionSource( PythonLaunchDescriptionSource(
@ -52,6 +52,6 @@ def generate_launch_description():
PythonLaunchDescriptionSource(os.path.join(pkg_gazebo_ros, 'launch', 'gzclient.launch.py')) PythonLaunchDescriptionSource(os.path.join(pkg_gazebo_ros, 'launch', 'gzclient.launch.py'))
), ),
spawn_entity, #spawn_entity,
bringup, bringup,
]) ])

View File

@ -7,17 +7,11 @@ from launch_ros.substitutions import FindPackageShare
def generate_launch_description(): def generate_launch_description():
# Launch arguments # Launch arguments
launch_args = [] launch_args = [DeclareLaunchArgument(
launch_args.append(
DeclareLaunchArgument(
name="robot_description", name="robot_description",
description="Robot description XML file." description="Robot description XML file."
) )]
)
# Configure robot_description # Configure robot_description
robot_description = {"robot_description": LaunchConfiguration("robot_description")} robot_description = {"robot_description": LaunchConfiguration("robot_description")}
@ -52,4 +46,5 @@ def generate_launch_description():
robot_state_publisher, robot_state_publisher,
joint_state_broadcaster, joint_state_broadcaster,
controller controller
]) ]
)

View File

@ -22,17 +22,18 @@ def generate_launch_description():
# ROS2 control demos via environment hook https://github.com/ros-controls/ros2_control_demos/tree/master/ros2_control_demo_description/rrbot_description # ROS2 control demos via environment hook https://github.com/ros-controls/ros2_control_demos/tree/master/ros2_control_demo_description/rrbot_description
# Also see https://colcon.readthedocs.io/en/released/developer/environment.html#dsv-files # Also see https://colcon.readthedocs.io/en/released/developer/environment.html#dsv-files
# Gazebo launch scripts append GAZEBO_MODEL_PATH with known paths, see https://github.com/ros-simulation/gazebo_ros_pkgs/blob/ab1ae5c05eda62674b36df74eb3be8c93cdc8761/gazebo_ros/launch/gzclient.launch.py#L26 # Gazebo launch scripts append GAZEBO_MODEL_PATH with known paths, see https://github.com/ros-simulation/gazebo_ros_pkgs/blob/ab1ae5c05eda62674b36df74eb3be8c93cdc8761/gazebo_ros/launch/gzclient.launch.py#L26
spawn_entity = Node(
package="gazebo_ros", #spawn_entity = Node(
executable="spawn_entity.py", # package="gazebo_ros",
arguments=[ # executable="spawn_entity.py",
"-topic", "robot_description", # arguments=[
"-entity", "iisy" # "-topic", "robot_description",
], # "-entity", "iisy"
output="screen" # ],
) # output="screen"
#)
return LaunchDescription([ return LaunchDescription([
gazebo, gazebo,
spawn_entity #spawn_entity
]) ])

View File

@ -276,10 +276,9 @@
</actuator> </actuator>
</transmission> </transmission>
<ros2_control name="lbr_hardware_interface" type="system"> <ros2_control name="IgnitionSystem" type="system">
<!-- define hardware including parameters, also gazebo -->
<hardware> <hardware>
<plugin>gazebo_ros2_control/GazeboSystem</plugin> <plugin>ign_ros2_control/IgnitionSystem</plugin>
</hardware> </hardware>
<!-- define lbr specific state interfaces as sensor, see https://github.com/ros-controls/roadmap/blob/master/design_drafts/components_architecture_and_urdf_examples.md --> <!-- define lbr specific state interfaces as sensor, see https://github.com/ros-controls/roadmap/blob/master/design_drafts/components_architecture_and_urdf_examples.md -->
@ -372,7 +371,7 @@
</ros2_control> </ros2_control>
<gazebo> <gazebo>
<plugin name="gazebo_ros2_control" filename="libgazebo_ros2_control.so"> <plugin name="ign_ros2_control::IgnitionROS2ControlPlugin" filename="$(find ign_ros2_control)/../../lib/libign_ros2_control-system.so">
<parameters>$(find iisy_config)/config/iisy_controllers.yml</parameters> <parameters>$(find iisy_config)/config/iisy_controllers.yml</parameters>
<robotNamespace>/iisy</robotNamespace> <robotNamespace>/iisy</robotNamespace>
</plugin> </plugin>