Skip to content
Closed
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
@@ -0,0 +1,16 @@
controller_manager:
ros__parameters:
update_rate: 100 # Hz

joint_trajectory_controller:
type: joint_trajectory_controller/JointTrajectoryController

joint_state_controller:
type: joint_state_controller/JointStateController

joint_trajectory_controller:
ros__parameters:
joints:
- joint1
- joint2
interface_name: position
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@destogl can you explain what that interface name does here? I'd assume that the joints are sufficiently described in the ros2_control tag with their control and state interfaces names.
What if I use position here and declare the joints as effort?

5 changes: 2 additions & 3 deletions ros2_control_demo_robot/description/rrbot/rrbot.gazebo.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -9,9 +9,8 @@ https://github.com/ros-simulation/gazebo_ros_demos/blob/kinetic-devel/rrbot_desc

<!-- ros_control plugin -->
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>/rrbot</robotNamespace>
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
<plugin name="gazebo_ros2_control" filename="libgazebo_ros2_control.so">
<parameters>$(find ros2_control_demo_robot)/controllers/rrbot_gazebo_forward_controller_position.yaml</parameters>
</plugin>
</gazebo>

Expand Down
Original file line number Diff line number Diff line change
@@ -1,15 +1,24 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

<xacro:macro name="rrbot_system_position_only" params="name prefix">
<xacro:macro name="rrbot_system_position_only" params="name prefix use_sim:='false' ">

<ros2_control name="${name}" type="system">
<hardware>
<plugin>ros2_control_demo_hardware/RRBotSystemPositionOnlyHardware</plugin>
<param name="example_param_hw_start_duration_sec">2.0</param>
<param name="example_param_hw_stop_duration_sec">3.0</param>
<param name="example_param_hw_slowdown">2.0</param>
</hardware>

<xacro:if value="$(arg use_sim)">
<hardware>
<plugin>gazebo_ros2_control/GazeboSystem</plugin>
</hardware>
</xacro:if>
<xacro:unless value="$(arg use_sim)">
<hardware>
<plugin>ros2_control_demo_hardware/RRBotSystemPositionOnlyHardware</plugin>
<param name="example_param_hw_start_duration_sec">2.0</param>
<param name="example_param_hw_stop_duration_sec">3.0</param>
<param name="example_param_hw_slowdown">2.0</param>
Comment on lines +16 to +18
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is not parsed in the plugin

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Maybe I misunderstood your comment, but this part is not included in the file generated by xacro because it is in the unless statement.
Should it be included ?

</hardware>
</xacro:unless>

<joint name="joint1">
<command_interface name="position">
<param name="min">-1</param>
Expand All @@ -29,4 +38,3 @@
</xacro:macro>

</robot>

Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,8 @@ Copied and modified from ROS1 example:
https://github.com/ros-simulation/gazebo_ros_demos/blob/kinetic-devel/rrbot_description/urdf/rrbot.xacro
-->
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="2dof_robot">

<xacro:arg name="use_sim" default="false" />

<!-- Import RRBot macro -->
<xacro:include filename="rrbot/rrbot.urdf.xacro" />
<!-- <xacro:include filename="$(find ros2_control_demo_robot)/description/rrbot/rrbot.urdf.xacro" /> -->
Expand Down Expand Up @@ -34,6 +35,6 @@ https://github.com/ros-simulation/gazebo_ros_demos/blob/kinetic-devel/rrbot_desc

<xacro:rrbot_gazebo prefix="" />

<xacro:rrbot_system_position_only name="RRBotSystemPositionOnly" prefix="" />
<xacro:rrbot_system_position_only name="RRBotSystemPositionOnly" prefix="" use_sim="$(arg use_sim)" />

</robot>
Original file line number Diff line number Diff line change
@@ -0,0 +1,60 @@
# Copyright 2021 Open Source Robotics Foundation, Inc.
#
# 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 IncludeLaunchDescription
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']),
)

robot_description_path = os.path.join(
get_package_share_directory('ros2_control_demo_robot'),
'description',
'rrbot_system_position_only.urdf.xacro')
robot_description_config = xacro.process_file(
robot_description_path,
mappings={'use_sim': 'true'})
robot_description = {'robot_description': robot_description_config.toxml()}

node_robot_state_publisher = Node(
package='robot_state_publisher',
executable='robot_state_publisher',
output='screen',
parameters=[robot_description]
)

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

return LaunchDescription([
gazebo,
node_robot_state_publisher,
spawn_entity,
])
3 changes: 3 additions & 0 deletions ros2_control_demo_robot/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,9 @@
<depend>hardware_interface</depend>
<depend>pluginlib</depend>
<depend>rclcpp</depend>
<depend>gazebo_ros2_control</depend>
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

you're missing an <exec_depend>xacro</exec_depend> here.

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thanks. Fixed in e6497f1


<exec_depend>xacro</exec_depend>

<depend>ros2_control_demo_hardware</depend>

Expand Down