Skip to content

Commit

Permalink
Revert "Switch fake to mock for ros2_control updates (#77)"
Browse files Browse the repository at this point in the history
This reverts commit aedef36.

Since it was only a deprecation warning, there is no need to break API
on humble.
  • Loading branch information
fmauch authored and RobertWilbrandt committed Jul 13, 2023
1 parent aedef36 commit c805a88
Show file tree
Hide file tree
Showing 3 changed files with 32 additions and 56 deletions.
70 changes: 23 additions & 47 deletions urdf/ur.ros2_control.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@

<xacro:macro name="ur_ros2_control" params="
name
use_mock_hardware:=false mock_sensor_commands:=false
use_fake_hardware:=false fake_sensor_commands:=false
sim_gazebo:=false
sim_ignition:=false
headless_mode:=false
Expand Down Expand Up @@ -31,12 +31,12 @@
<xacro:if value="${sim_ignition}">
<plugin>ign_ros2_control/IgnitionSystem</plugin>
</xacro:if>
<xacro:if value="${use_mock_hardware}">
<xacro:if value="${use_fake_hardware}">
<plugin>mock_components/GenericSystem</plugin>
<param name="mock_sensor_commands">${mock_sensor_commands}</param>
<param name="fake_sensor_commands">${fake_sensor_commands}</param>
<param name="state_following_offset">0.0</param>
</xacro:if>
<xacro:unless value="${use_mock_hardware or sim_gazebo or sim_ignition}">
<xacro:unless value="${use_fake_hardware or sim_gazebo or sim_ignition}">
<plugin>ur_robot_driver/URPositionHardwareInterface</plugin>
<param name="robot_ip">${robot_ip}</param>
<param name="script_filename">${script_filename}</param>
Expand Down Expand Up @@ -75,15 +75,11 @@
<param name="max">3.15</param>
</command_interface>
<state_interface name="position">
<!-- initial position for the mock system and simulation -->
<!-- initial position for the FakeSystem and simulation -->
<param name="initial_value">${initial_positions['shoulder_pan_joint']}</param>
</state_interface>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="effort">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="${tf_prefix}shoulder_lift_joint">
<command_interface name="position">
Expand All @@ -95,15 +91,11 @@
<param name="max">3.15</param>
</command_interface>
<state_interface name="position">
<!-- initial position for the mock system and simulation -->
<!-- initial position for the FakeSystem and simulation -->
<param name="initial_value">${initial_positions['shoulder_lift_joint']}</param>
</state_interface>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="effort">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="${tf_prefix}elbow_joint">
<command_interface name="position">
Expand All @@ -115,15 +107,11 @@
<param name="max">3.15</param>
</command_interface>
<state_interface name="position">
<!-- initial position for the mock system and simulation -->
<!-- initial position for the FakeSystem and simulation -->
<param name="initial_value">${initial_positions['elbow_joint']}</param>
</state_interface>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="effort">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="${tf_prefix}wrist_1_joint">
<command_interface name="position">
Expand All @@ -135,15 +123,11 @@
<param name="max">3.2</param>
</command_interface>
<state_interface name="position">
<!-- initial position for the mock system and simulation -->
<!-- initial position for the FakeSystem and simulation -->
<param name="initial_value">${initial_positions['wrist_1_joint']}</param>
</state_interface>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="effort">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="${tf_prefix}wrist_2_joint">
<command_interface name="position">
Expand All @@ -155,15 +139,11 @@
<param name="max">3.2</param>
</command_interface>
<state_interface name="position">
<!-- initial position for the mock system and simulation -->
<!-- initial position for the FakeSystem and simulation -->
<param name="initial_value">${initial_positions['wrist_2_joint']}</param>
</state_interface>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="effort">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="${tf_prefix}wrist_3_joint">
<command_interface name="position">
Expand All @@ -175,15 +155,11 @@
<param name="max">3.2</param>
</command_interface>
<state_interface name="position">
<!-- initial position for the mock system and simulation -->
<!-- initial position for the FakeSystem and simulation -->
<param name="initial_value">${initial_positions['wrist_3_joint']}</param>
</state_interface>
<state_interface name="velocity">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="effort">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>

<xacro:unless value="${sim_gazebo or sim_ignition}">
Expand All @@ -196,7 +172,7 @@
<state_interface name="torque.z"/>
</sensor>

<!-- NOTE The following are joints used only for testing with mock hardware and will change in the future -->
<!-- NOTE The following are joints used only for testing with fake hardware and will change in the future -->
<gpio name="${tf_prefix}speed_scaling">
<state_interface name="speed_scaling_factor"/>
<param name="initial_speed_scaling_factor">1</param>
Expand Down
10 changes: 5 additions & 5 deletions urdf/ur.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -39,13 +39,13 @@
<xacro:arg name="tool_tcp_port" default="54321" />

<!-- Simulation parameters -->
<xacro:arg name="use_mock_hardware" default="false" />
<xacro:arg name="mock_sensor_commands" default="false" />
<xacro:arg name="use_fake_hardware" default="false" />
<xacro:arg name="fake_sensor_commands" default="false" />
<xacro:arg name="sim_gazebo" default="false" />
<xacro:arg name="sim_ignition" default="false" />
<xacro:arg name="simulation_controllers" default="" />

<!-- initial position for simulations (Mock Hardware, Gazebo, Ignition) -->
<!-- initial position for simulations (Fake Hardware, Gazebo, Ignition) -->
<xacro:arg name="initial_positions_file" default="$(find ur_description)/config/initial_positions.yaml"/>

<!-- convert to property to use substitution in function -->
Expand All @@ -67,8 +67,8 @@
safety_limits="$(arg safety_limits)"
safety_pos_margin="$(arg safety_pos_margin)"
safety_k_position="$(arg safety_k_position)"
use_mock_hardware="$(arg use_mock_hardware)"
mock_sensor_commands="$(arg mock_sensor_commands)"
use_fake_hardware="$(arg use_fake_hardware)"
fake_sensor_commands="$(arg fake_sensor_commands)"
sim_gazebo="$(arg sim_gazebo)"
sim_ignition="$(arg sim_ignition)"
headless_mode="$(arg headless_mode)"
Expand Down
8 changes: 4 additions & 4 deletions urdf/ur_macro.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -66,8 +66,8 @@
safety_limits:=false
safety_pos_margin:=0.15
safety_k_position:=20
use_mock_hardware:=false
mock_sensor_commands:=false
use_fake_hardware:=false
fake_sensor_commands:=false
sim_gazebo:=false
sim_ignition:=false
headless_mode:=false
Expand Down Expand Up @@ -109,9 +109,9 @@
<!-- ros2 control instance -->
<xacro:ur_ros2_control
name="${name}"
use_mock_hardware="${use_mock_hardware}"
use_fake_hardware="${use_fake_hardware}"
initial_positions="${initial_positions}"
mock_sensor_commands="${mock_sensor_commands}"
fake_sensor_commands="${fake_sensor_commands}"
headless_mode="${headless_mode}"
sim_gazebo="${sim_gazebo}"
sim_ignition="${sim_ignition}"
Expand Down

0 comments on commit c805a88

Please sign in to comment.