Skip to content

Commit 3b0446c

Browse files
committed
showcase for transmissions in mock hw
1 parent 044db05 commit 3b0446c

File tree

3 files changed

+28
-6
lines changed

3 files changed

+28
-6
lines changed

example_8/bringup/launch/rrbot_transmissions_system_position_only.launch.py

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,14 @@ def generate_launch_description():
3939
"slowdown", default_value="50.0", description="Slowdown factor of the RRbot."
4040
)
4141
)
42+
declared_arguments.append(
43+
DeclareLaunchArgument(
44+
"use_mock_hardware",
45+
default_value="false",
46+
description="Use mock hardware instead of real one.",
47+
choices=["true", "false"],
48+
)
49+
)
4250
declared_arguments.append(
4351
DeclareLaunchArgument(
4452
"robot_controller",
@@ -57,6 +65,7 @@ def generate_launch_description():
5765
# Initialize Arguments
5866
prefix = LaunchConfiguration("prefix")
5967
slowdown = LaunchConfiguration("slowdown")
68+
use_mock_hardware = LaunchConfiguration("use_mock_hardware")
6069
robot_controller = LaunchConfiguration("robot_controller")
6170
gui = LaunchConfiguration("gui")
6271

@@ -78,6 +87,9 @@ def generate_launch_description():
7887
" ",
7988
"slowdown:=",
8089
slowdown,
90+
" ",
91+
"use_mock_hardware:=",
92+
use_mock_hardware,
8193
]
8294
)
8395
robot_description = {"robot_description": robot_description_content}

example_8/description/ros2_control/rrbot_transmissions_system_position_only.ros2_control.xacro

Lines changed: 10 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,12 +1,18 @@
11
<?xml version="1.0"?>
22
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
33

4-
<xacro:macro name="rrbot_transmissions_system_position_only" params="name prefix slowdown:=2.0">
4+
<xacro:macro name="rrbot_transmissions_system_position_only" params="name prefix slowdown:=^|2.0 use_mock_hardware:=^|false mock_sensor_commands:=^|false">
55

66
<ros2_control name="${name}" type="system">
77

88
<hardware>
9-
<plugin>ros2_control_demo_example_8/RRBotTransmissionsSystemPositionOnlyHardware</plugin>
9+
<xacro:if value="${use_mock_hardware}">
10+
<plugin>mock_components/GenericSystem</plugin>
11+
<param name="mock_sensor_commands">${mock_sensor_commands}</param>
12+
</xacro:if>
13+
<xacro:unless value="${use_mock_hardware}">
14+
<plugin>ros2_control_demo_example_8/RRBotTransmissionsSystemPositionOnlyHardware</plugin>
15+
</xacro:unless>
1016
<param name="actuator_slowdown">${slowdown}</param>
1117
</hardware>
1218

@@ -31,7 +37,7 @@
3137
<actuator name="actuator1" role="actuator1"/>
3238
<joint name="joint1" role="joint1">
3339
<mechanical_reduction>2.0</mechanical_reduction>
34-
<offset>0.0</offset>
40+
<offset>0.2</offset>
3541
</joint>
3642
</transmission>
3743

@@ -40,7 +46,7 @@
4046
<actuator name="actuator2" role="actuator2"/>
4147
<joint name="joint2" role="joint2">
4248
<mechanical_reduction>4.0</mechanical_reduction>
43-
<offset>0.0</offset>
49+
<offset>-0.2</offset>
4450
</joint>
4551
</transmission>
4652
</ros2_control>

example_8/description/urdf/rrbot_transmissions_system_position_only.urdf.xacro

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@ https://github.com/ros-simulation/gazebo_ros_demos/blob/kinetic-devel/rrbot_desc
99
<!-- Enable setting arguments from the launch file -->
1010
<xacro:arg name="prefix" default="" />
1111
<xacro:arg name="slowdown" default="100.0" />
12+
<xacro:arg name="use_mock_hardware" default="false" />
1213

1314
<!-- Import RRBot macro -->
1415
<xacro:include filename="$(find ros2_control_demo_description)/rrbot/urdf/rrbot_description.urdf.xacro" />
@@ -27,7 +28,10 @@ https://github.com/ros-simulation/gazebo_ros_demos/blob/kinetic-devel/rrbot_desc
2728
</xacro:rrbot>
2829

2930
<xacro:rrbot_transmissions_system_position_only
30-
name="RRBotTransmissionsSystemPositionOnly" prefix="$(arg prefix)"
31-
slowdown="$(arg slowdown)" />
31+
name="RRBotTransmissionsSystemPositionOnly"
32+
prefix="$(arg prefix)"
33+
slowdown="$(arg slowdown)"
34+
use_mock_hardware="$(arg use_mock_hardware)"
35+
/>
3236

3337
</robot>

0 commit comments

Comments
 (0)