Skip to content

Commit

Permalink
Rename "fake_hardware" to "mock_hardware".
Browse files Browse the repository at this point in the history
  • Loading branch information
destogl committed Mar 8, 2023
1 parent 161aaa9 commit 6b354fd
Show file tree
Hide file tree
Showing 16 changed files with 61 additions and 61 deletions.
12 changes: 6 additions & 6 deletions example_3/bringup/launch/rrbot_base.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -65,17 +65,17 @@ def generate_launch_description():
)
declared_arguments.append(
DeclareLaunchArgument(
"use_fake_hardware",
"use_mock_hardware",
default_value="true",
description="Start robot with fake hardware mirroring command to its states.",
description="Start robot with mock hardware mirroring command to its states.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"mock_sensor_commands",
default_value="false",
description="Enable fake command interfaces for sensors used for simple simulations. \
Used only if 'use_fake_hardware' parameter is true.",
Used only if 'use_mock_hardware' parameter is true.",
)
)
declared_arguments.append(
Expand Down Expand Up @@ -104,7 +104,7 @@ def generate_launch_description():
description_package = LaunchConfiguration("description_package")
description_file = LaunchConfiguration("description_file")
prefix = LaunchConfiguration("prefix")
use_fake_hardware = LaunchConfiguration("use_fake_hardware")
use_mock_hardware = LaunchConfiguration("use_mock_hardware")
mock_sensor_commands = LaunchConfiguration("mock_sensor_commands")
slowdown = LaunchConfiguration("slowdown")
robot_controller = LaunchConfiguration("robot_controller")
Expand All @@ -122,8 +122,8 @@ def generate_launch_description():
"prefix:=",
prefix,
" ",
"use_fake_hardware:=",
use_fake_hardware,
"use_mock_hardware:=",
use_mock_hardware,
" ",
"mock_sensor_commands:=",
mock_sensor_commands,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ def generate_launch_description():
"controllers_file": "rrbot_multi_interface_forward_controllers.yaml",
"description_file": "rrbot_system_multi_interface.urdf.xacro",
"prefix": prefix,
"use_fake_hardware": "false",
"use_mock_hardware": "false",
"mock_sensor_commands": "false",
"slowdown": slowdown,
"robot_controller": robot_controller,
Expand Down
Original file line number Diff line number Diff line change
@@ -1,17 +1,17 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

<xacro:macro name="rrbot_system_multi_interface" params="name prefix use_fake_hardware:=^|true mock_sensor_commands:=^|false slowdown:=2.0">
<xacro:macro name="rrbot_system_multi_interface" params="name prefix use_mock_hardware:=^|true mock_sensor_commands:=^|false slowdown:=2.0">

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

<hardware>
<xacro:if value="${use_fake_hardware}">
<xacro:if value="${use_mock_hardware}">
<plugin>mock_components/GenericSystem</plugin>
<param name="mock_sensor_commands">${mock_sensor_commands}</param>
<param name="state_following_offset">0.0</param>
</xacro:if>
<xacro:unless value="${use_fake_hardware}">
<xacro:unless value="${use_mock_hardware}">
<plugin>ros2_control_demo_example_3/RRBotSystemMultiInterfaceHardware</plugin>
<param name="example_param_hw_start_duration_sec">0.0</param>
<param name="example_param_hw_stop_duration_sec">3.0</param>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@ https://github.com/ros-simulation/gazebo_ros_demos/blob/kinetic-devel/rrbot_desc
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="2dof_robot">

<!-- Enable setting arguments from the launch file -->
<xacro:arg name="use_fake_hardware" default="false" />
<xacro:arg name="use_mock_hardware" default="false" />
<xacro:arg name="mock_sensor_commands" default="false" />
<xacro:arg name="prefix" default="" />
<xacro:arg name="slowdown" default="100.0" />
Expand All @@ -30,7 +30,7 @@ https://github.com/ros-simulation/gazebo_ros_demos/blob/kinetic-devel/rrbot_desc

<xacro:rrbot_system_multi_interface
name="RRBotSystemMultiInterface" prefix="$(arg prefix)"
use_fake_hardware="$(arg use_fake_hardware)"
use_mock_hardware="$(arg use_mock_hardware)"
mock_sensor_commands="$(arg mock_sensor_commands)"
slowdown="$(arg slowdown)" />

Expand Down
12 changes: 6 additions & 6 deletions example_4/bringup/launch/rrbot_base.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -65,17 +65,17 @@ def generate_launch_description():
)
declared_arguments.append(
DeclareLaunchArgument(
"use_fake_hardware",
"use_mock_hardware",
default_value="true",
description="Start robot with fake hardware mirroring command to its states.",
description="Start robot with mock hardware mirroring command to its states.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"mock_sensor_commands",
default_value="false",
description="Enable fake command interfaces for sensors used for simple simulations. \
Used only if 'use_fake_hardware' parameter is true.",
Used only if 'use_mock_hardware' parameter is true.",
)
)
declared_arguments.append(
Expand Down Expand Up @@ -104,7 +104,7 @@ def generate_launch_description():
description_package = LaunchConfiguration("description_package")
description_file = LaunchConfiguration("description_file")
prefix = LaunchConfiguration("prefix")
use_fake_hardware = LaunchConfiguration("use_fake_hardware")
use_mock_hardware = LaunchConfiguration("use_mock_hardware")
mock_sensor_commands = LaunchConfiguration("mock_sensor_commands")
slowdown = LaunchConfiguration("slowdown")
robot_controller = LaunchConfiguration("robot_controller")
Expand All @@ -122,8 +122,8 @@ def generate_launch_description():
"prefix:=",
prefix,
" ",
"use_fake_hardware:=",
use_fake_hardware,
"use_mock_hardware:=",
use_mock_hardware,
" ",
"mock_sensor_commands:=",
mock_sensor_commands,
Expand Down
10 changes: 5 additions & 5 deletions example_4/bringup/launch/rrbot_system_with_sensor.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -35,17 +35,17 @@ def generate_launch_description():
)
declared_arguments.append(
DeclareLaunchArgument(
"use_fake_hardware",
"use_mock_hardware",
default_value="false",
description="Start robot with fake hardware mirroring command to its states.",
description="Start robot with mock hardware mirroring command to its states.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"mock_sensor_commands",
default_value="false",
description="Enable fake command interfaces for sensors used for simple simulations. \
Used only if 'use_fake_hardware' parameter is true.",
Used only if 'use_mock_hardware' parameter is true.",
)
)
declared_arguments.append(
Expand All @@ -58,7 +58,7 @@ def generate_launch_description():

# Initialize Arguments
prefix = LaunchConfiguration("prefix")
use_fake_hardware = LaunchConfiguration("use_fake_hardware")
use_mock_hardware = LaunchConfiguration("use_mock_hardware")
mock_sensor_commands = LaunchConfiguration("mock_sensor_commands")
slowdown = LaunchConfiguration("slowdown")

Expand All @@ -68,7 +68,7 @@ def generate_launch_description():
"controllers_file": "rrbot_with_sensor_controllers.yaml",
"description_file": "rrbot_system_with_sensor.urdf.xacro",
"prefix": prefix,
"use_fake_hardware": use_fake_hardware,
"use_mock_hardware": use_mock_hardware,
"mock_sensor_commands": mock_sensor_commands,
"slowdown": slowdown,
}.items(),
Expand Down
Original file line number Diff line number Diff line change
@@ -1,17 +1,17 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

<xacro:macro name="rrbot_system_with_sensor" params="name prefix use_fake_hardware:=^|true mock_sensor_commands:=^|false slowdown:=2.0">
<xacro:macro name="rrbot_system_with_sensor" params="name prefix use_mock_hardware:=^|true mock_sensor_commands:=^|false slowdown:=2.0">

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

<hardware>
<xacro:if value="${use_fake_hardware}">
<xacro:if value="${use_mock_hardware}">
<plugin>mock_components/GenericSystem</plugin>
<param name="mock_sensor_commands">${mock_sensor_commands}</param>
<param name="state_following_offset">0.0</param>
</xacro:if>
<xacro:unless value="${use_fake_hardware}">
<xacro:unless value="${use_mock_hardware}">
<plugin>ros2_control_demo_example_4/RRBotSystemWithSensorHardware</plugin>
<param name="example_param_hw_start_duration_sec">0.0</param>
<param name="example_param_hw_stop_duration_sec">3.0</param>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@ https://github.com/ros-simulation/gazebo_ros_demos/blob/kinetic-devel/rrbot_desc
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="2dof_robot">

<!-- Enable setting arguments from the launch file -->
<xacro:arg name="use_fake_hardware" default="false" />
<xacro:arg name="use_mock_hardware" default="false" />
<xacro:arg name="mock_sensor_commands" default="false" />
<xacro:arg name="prefix" default="" />
<xacro:arg name="slowdown" default="50.0" />
Expand All @@ -30,7 +30,7 @@ https://github.com/ros-simulation/gazebo_ros_demos/blob/kinetic-devel/rrbot_desc

<xacro:rrbot_system_with_sensor
name="RRBotSystemWithSensor" prefix="$(arg prefix)"
use_fake_hardware="$(arg use_fake_hardware)"
use_mock_hardware="$(arg use_mock_hardware)"
mock_sensor_commands="$(arg mock_sensor_commands)"
slowdown="$(arg slowdown)" />

Expand Down
12 changes: 6 additions & 6 deletions example_5/bringup/launch/rrbot_base.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -65,17 +65,17 @@ def generate_launch_description():
)
declared_arguments.append(
DeclareLaunchArgument(
"use_fake_hardware",
"use_mock_hardware",
default_value="true",
description="Start robot with fake hardware mirroring command to its states.",
description="Start robot with mock hardware mirroring command to its states.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"mock_sensor_commands",
default_value="false",
description="Enable fake command interfaces for sensors used for simple simulations. \
Used only if 'use_fake_hardware' parameter is true.",
Used only if 'use_mock_hardware' parameter is true.",
)
)
declared_arguments.append(
Expand Down Expand Up @@ -104,7 +104,7 @@ def generate_launch_description():
description_package = LaunchConfiguration("description_package")
description_file = LaunchConfiguration("description_file")
prefix = LaunchConfiguration("prefix")
use_fake_hardware = LaunchConfiguration("use_fake_hardware")
use_mock_hardware = LaunchConfiguration("use_mock_hardware")
mock_sensor_commands = LaunchConfiguration("mock_sensor_commands")
slowdown = LaunchConfiguration("slowdown")
robot_controller = LaunchConfiguration("robot_controller")
Expand All @@ -122,8 +122,8 @@ def generate_launch_description():
"prefix:=",
prefix,
" ",
"use_fake_hardware:=",
use_fake_hardware,
"use_mock_hardware:=",
use_mock_hardware,
" ",
"mock_sensor_commands:=",
mock_sensor_commands,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,17 +35,17 @@ def generate_launch_description():
)
declared_arguments.append(
DeclareLaunchArgument(
"use_fake_hardware",
"use_mock_hardware",
default_value="false",
description="Start robot with fake hardware mirroring command to its states.",
description="Start robot with mock hardware mirroring command to its states.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"mock_sensor_commands",
default_value="false",
description="Enable fake command interfaces for sensors used for simple simulations. \
Used only if 'use_fake_hardware' parameter is true.",
Used only if 'use_mock_hardware' parameter is true.",
)
)

Expand All @@ -59,7 +59,7 @@ def generate_launch_description():

# Initialize Arguments
prefix = LaunchConfiguration("prefix")
use_fake_hardware = LaunchConfiguration("use_fake_hardware")
use_mock_hardware = LaunchConfiguration("use_mock_hardware")
mock_sensor_commands = LaunchConfiguration("mock_sensor_commands")
slowdown = LaunchConfiguration("slowdown")

Expand All @@ -69,7 +69,7 @@ def generate_launch_description():
"controllers_file": "rrbot_with_external_sensor_controllers.yaml",
"description_file": "rrbot_system_with_external_sensor.urdf.xacro",
"prefix": prefix,
"use_fake_hardware": use_fake_hardware,
"use_mock_hardware": use_mock_hardware,
"mock_sensor_commands": mock_sensor_commands,
"slowdown": slowdown,
}.items(),
Expand Down
Original file line number Diff line number Diff line change
@@ -1,16 +1,16 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

<xacro:macro name="external_rrbot_force_torque_sensor" params="name prefix use_fake_hardware:=^|true mock_sensor_commands:=^|false">
<xacro:macro name="external_rrbot_force_torque_sensor" params="name prefix use_mock_hardware:=^|true mock_sensor_commands:=^|false">

<ros2_control name="${name}" type="sensor">
<hardware>
<xacro:if value="${use_fake_hardware}">
<xacro:if value="${use_mock_hardware}">
<plugin>mock_components/GenericSystem</plugin>
<param name="mock_sensor_commands">${mock_sensor_commands}</param>
<param name="state_following_offset">0.0</param>
</xacro:if>
<xacro:unless value="${use_fake_hardware}">
<xacro:unless value="${use_mock_hardware}">
<plugin>ros2_control_demo_example_5/ExternalRRBotForceTorqueSensorHardware</plugin>
<param name="example_param_hw_start_duration_sec">0.0</param>
<param name="example_param_hw_stop_duration_sec">3.0</param>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,17 +1,17 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

<xacro:macro name="rrbot_system_position_only" params="name prefix use_fake_hardware:=^|true mock_sensor_commands:=^|false slowdown:=2.0">
<xacro:macro name="rrbot_system_position_only" params="name prefix use_mock_hardware:=^|true mock_sensor_commands:=^|false slowdown:=2.0">

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

<hardware>
<xacro:if value="${use_fake_hardware}">
<xacro:if value="${use_mock_hardware}">
<plugin>mock_components/GenericSystem</plugin>
<param name="mock_sensor_commands">${mock_sensor_commands}</param>
<param name="state_following_offset">0.0</param>
</xacro:if>
<xacro:unless value="${use_fake_hardware}">
<xacro:unless value="${use_mock_hardware}">
<plugin>ros2_control_demo_example_5/RRBotSystemPositionOnlyHardware</plugin>
<param name="example_param_hw_start_duration_sec">0.0</param>
<param name="example_param_hw_stop_duration_sec">3.0</param>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@ https://github.com/ros-simulation/gazebo_ros_demos/blob/kinetic-devel/rrbot_desc
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="2dof_robot">

<!-- Enable setting arguments from the launch file -->
<xacro:arg name="use_fake_hardware" default="true" />
<xacro:arg name="use_mock_hardware" default="true" />
<xacro:arg name="mock_sensor_commands" default="false" />
<xacro:arg name="prefix" default="" />
<xacro:arg name="slowdown" default="50.0" />
Expand All @@ -33,12 +33,12 @@ https://github.com/ros-simulation/gazebo_ros_demos/blob/kinetic-devel/rrbot_desc

<xacro:rrbot_system_position_only
name="RRBotSystemPositionOnly" prefix="$(arg prefix)"
use_fake_hardware="$(arg use_fake_hardware)"
use_mock_hardware="$(arg use_mock_hardware)"
mock_sensor_commands="$(arg mock_sensor_commands)"
slowdown="$(arg slowdown)" />

<xacro:external_rrbot_force_torque_sensor
name="ExternalRRBotFTSensor" prefix="$(arg prefix)"
use_fake_hardware="$(arg use_fake_hardware)"
use_mock_hardware="$(arg use_mock_hardware)"
mock_sensor_commands="$(arg mock_sensor_commands)" />
</robot>
12 changes: 6 additions & 6 deletions example_6/bringup/launch/rrbot_base.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -65,17 +65,17 @@ def generate_launch_description():
)
declared_arguments.append(
DeclareLaunchArgument(
"use_fake_hardware",
"use_mock_hardware",
default_value="true",
description="Start robot with fake hardware mirroring command to its states.",
description="Start robot with mock hardware mirroring command to its states.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"mock_sensor_commands",
default_value="false",
description="Enable fake command interfaces for sensors used for simple simulations. \
Used only if 'use_fake_hardware' parameter is true.",
Used only if 'use_mock_hardware' parameter is true.",
)
)
declared_arguments.append(
Expand Down Expand Up @@ -104,7 +104,7 @@ def generate_launch_description():
description_package = LaunchConfiguration("description_package")
description_file = LaunchConfiguration("description_file")
prefix = LaunchConfiguration("prefix")
use_fake_hardware = LaunchConfiguration("use_fake_hardware")
use_mock_hardware = LaunchConfiguration("use_mock_hardware")
mock_sensor_commands = LaunchConfiguration("mock_sensor_commands")
slowdown = LaunchConfiguration("slowdown")
robot_controller = LaunchConfiguration("robot_controller")
Expand All @@ -122,8 +122,8 @@ def generate_launch_description():
"prefix:=",
prefix,
" ",
"use_fake_hardware:=",
use_fake_hardware,
"use_mock_hardware:=",
use_mock_hardware,
" ",
"mock_sensor_commands:=",
mock_sensor_commands,
Expand Down
Loading

0 comments on commit 6b354fd

Please sign in to comment.