Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add namespaced example #367

Closed
wants to merge 3 commits into from
Closed
Show file tree
Hide file tree
Changes from 1 commit
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
@@ -0,0 +1,19 @@
/my_ns/controller_manager:
ros__parameters:
update_rate: 100 # Hz

joint_trajectory_controller:
type: joint_trajectory_controller/JointTrajectoryController

joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster

/my_ns/joint_trajectory_controller:
ros__parameters:
joints:
- slider_to_cart
command_interfaces:
- position
state_interfaces:
- position
- velocity
Original file line number Diff line number Diff line change
@@ -0,0 +1,91 @@
# Copyright 2020 Open Source Robotics Foundation, Inc.
christophfroehlich marked this conversation as resolved.
Show resolved Hide resolved
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# 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 ExecuteProcess, IncludeLaunchDescription, RegisterEventHandler
from launch.event_handlers import OnProcessExit
from launch.launch_description_sources import PythonLaunchDescriptionSource

from launch_ros.actions import Node

import xacro


def generate_launch_description():
gazebo = IncludeLaunchDescription(
PythonLaunchDescriptionSource([os.path.join(
get_package_share_directory('gazebo_ros'), 'launch'), '/gazebo.launch.py']),
)

gazebo_ros2_control_demos_path = os.path.join(
get_package_share_directory('gazebo_ros2_control_demos'))

xacro_file = os.path.join(gazebo_ros2_control_demos_path,
'urdf',
'test_cart_position_namespaced.xacro.urdf')

doc = xacro.parse(open(xacro_file))
xacro.process_doc(doc)
params = {'robot_description': doc.toxml()}

node_robot_state_publisher = Node(
package='robot_state_publisher',
executable='robot_state_publisher',
namespace="my_ns",
output='screen',
parameters=[params]
)

spawn_entity = Node(package='gazebo_ros', executable='spawn_entity.py',
namespace="my_ns",
arguments=['-topic', 'robot_description',
'-entity', 'cart'],
output='screen')

load_joint_state_broadcaster = ExecuteProcess(
cmd=['ros2', 'control', 'load_controller', '--set-state', 'active',
'-c', '/my_ns/controller_manager',
'joint_state_broadcaster'],
output='screen'
)

load_joint_trajectory_controller = ExecuteProcess(
cmd=['ros2', 'control', 'load_controller', '--set-state', 'active',
'-c', '/my_ns/controller_manager',
'joint_trajectory_controller'],
output='screen'
)

return LaunchDescription([
RegisterEventHandler(
event_handler=OnProcessExit(
target_action=spawn_entity,
on_exit=[load_joint_state_broadcaster],
)
),
RegisterEventHandler(
event_handler=OnProcessExit(
target_action=load_joint_state_broadcaster,
on_exit=[load_joint_trajectory_controller],
)
),
gazebo,
node_robot_state_publisher,
spawn_entity,
])
Original file line number Diff line number Diff line change
@@ -0,0 +1,72 @@
<?xml version="1.0" ?>
<robot name="cart">
<link name="world"/>
<link name="slideBar">
<visual>
<geometry>
<box size="30 0.05 0.05"/>
</geometry>
<origin xyz="0 0 0"/>
<material name="green">
<color rgba="0 0.8 .8 1"/>
</material>
</visual>
<inertial>
<mass value="100"/>
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
</inertial>
</link>
<link name="cart">
<visual>
<geometry>
<box size="0.5 0.5 0.2"/>
</geometry>
<origin xyz="0 0 0"/>
<material name="blue">
<color rgba="0 0 .8 1"/>
</material>
</visual>
<inertial>
<mass value="1"/>
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
</inertial>
</link>
<joint name="world_to_base" type="fixed">
<origin rpy="0 0 0" xyz="0 0 1"/>
<parent link="world"/>
<child link="slideBar"/>
</joint>
<joint name="slider_to_cart" type="prismatic">
<axis xyz="1 0 0"/>
<origin xyz="0.0 0.0 0.0"/>
<parent link="slideBar"/>
<child link="cart"/>
<limit effort="1000.0" lower="-15" upper="15" velocity="30"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<ros2_control name="GazeboSystem" type="system">
<hardware>
<plugin>gazebo_ros2_control/GazeboSystem</plugin>
</hardware>
<joint name="slider_to_cart">
<command_interface name="position">
<param name="min">-15</param>
<param name="max">15</param>
</command_interface>
<state_interface name="position">
<param name="initial_value">1.0</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
</ros2_control>

<gazebo>
<plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control">
<ros>
<namespace>my_ns</namespace>
</ros>
<parameters>$(find gazebo_ros2_control_demos)/config/cart_controller_position_namespaced.yaml</parameters>
</plugin>
</gazebo>
</robot>