Skip to content

Commit 84903de

Browse files
committed
Code formatting
1 parent 3bb779b commit 84903de

File tree

3 files changed

+18
-36
lines changed

3 files changed

+18
-36
lines changed

ur_controllers/src/force_mode_controller.cpp

Lines changed: 6 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -197,18 +197,12 @@ controller_interface::return_type ur_controllers::ForceModeController::update(co
197197
command_interfaces_[CommandInterfaces::FORCE_MODE_SELECTION_VECTOR_RZ].set_value(
198198
force_mode_parameters->selection_vec[5]);
199199

200-
command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_X].set_value(
201-
force_mode_parameters->wrench.force.x);
202-
command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_Y].set_value(
203-
force_mode_parameters->wrench.force.y);
204-
command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_Z].set_value(
205-
force_mode_parameters->wrench.force.z);
206-
command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_RX].set_value(
207-
force_mode_parameters->wrench.torque.x);
208-
command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_RY].set_value(
209-
force_mode_parameters->wrench.torque.y);
210-
command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_RZ].set_value(
211-
force_mode_parameters->wrench.torque.z);
200+
command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_X].set_value(force_mode_parameters->wrench.force.x);
201+
command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_Y].set_value(force_mode_parameters->wrench.force.y);
202+
command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_Z].set_value(force_mode_parameters->wrench.force.z);
203+
command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_RX].set_value(force_mode_parameters->wrench.torque.x);
204+
command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_RY].set_value(force_mode_parameters->wrench.torque.y);
205+
command_interfaces_[CommandInterfaces::FORCE_MODE_WRENCH_RZ].set_value(force_mode_parameters->wrench.torque.z);
212206

213207
command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_X].set_value(force_mode_parameters->limits[0]);
214208
command_interfaces_[CommandInterfaces::FORCE_MODE_LIMITS_Y].set_value(force_mode_parameters->limits[1]);

ur_controllers/test/test_load_force_mode_controller.cpp

Lines changed: 7 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -35,22 +35,20 @@
3535

3636
TEST(TestLoadForceModeController, load_controller)
3737
{
38-
std::shared_ptr<rclcpp::Executor> executor =
39-
std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
38+
std::shared_ptr<rclcpp::Executor> executor = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
4039

41-
controller_manager::ControllerManager cm{
42-
executor, ros2_control_test_assets::minimal_robot_urdf, true, "test_controller_manager"};
40+
controller_manager::ControllerManager cm{ executor, ros2_control_test_assets::minimal_robot_urdf, true,
41+
"test_controller_manager" };
4342

44-
const std::string test_file_path =
45-
std::string{TEST_FILES_DIRECTORY} + "/force_mode_controller_params.yaml";
46-
cm.set_parameter({"test_force_mode_controller.params_file", test_file_path});
43+
const std::string test_file_path = std::string{ TEST_FILES_DIRECTORY } + "/force_mode_controller_params.yaml";
44+
cm.set_parameter({ "test_force_mode_controller.params_file", test_file_path });
4745

48-
cm.set_parameter({"test_force_mode_controller.type", "ur_controllers/ForceModeController"});
46+
cm.set_parameter({ "test_force_mode_controller.type", "ur_controllers/ForceModeController" });
4947

5048
ASSERT_NE(cm.load_controller("test_force_mode_controller"), nullptr);
5149
}
5250

53-
int main(int argc, char * argv[])
51+
int main(int argc, char* argv[])
5452
{
5553
::testing::InitGoogleMock(&argc, argv);
5654
rclcpp::init(argc, argv);

ur_robot_driver/test/integration_test_force_mode.py

Lines changed: 5 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -27,8 +27,6 @@
2727
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
2828
# POSSIBILITY OF SUCH DAMAGE.
2929

30-
import copy
31-
import logging
3230
import os
3331
import sys
3432
import time
@@ -52,22 +50,18 @@
5250
Quaternion,
5351
Point,
5452
Twist,
55-
WrenchStamped,
5653
Wrench,
5754
Vector3,
5855
)
59-
from ur_msgs.srv import SetForceMode
6056

6157
sys.path.append(os.path.dirname(__file__))
6258
from test_common import ( # noqa: E402
63-
ActionInterface,
6459
ControllerManagerInterface,
6560
DashboardInterface,
6661
ForceModeInterface,
6762
IoStatusInterface,
6863
ConfigurationInterface,
6964
generate_driver_test_description,
70-
ROBOT_JOINTS,
7165
)
7266

7367
TIMEOUT_EXECUTE_TRAJECTORY = 30
@@ -106,9 +100,7 @@ def init_robot(self):
106100
def setUp(self):
107101
self._dashboard_interface.start_robot()
108102
time.sleep(1)
109-
self.assertTrue(
110-
self._io_status_controller_interface.resend_robot_program().success
111-
)
103+
self.assertTrue(self._io_status_controller_interface.resend_robot_program().success)
112104
self.tf_buffer = Buffer()
113105
self.tf_listener = TransformListener(self.tf_buffer, self.node)
114106

@@ -155,7 +147,7 @@ def test_force_mode_controller(self, tf_prefix):
155147
speed_limits = Twist()
156148
speed_limits.linear = Vector3(x=0.0, y=0.0, z=1.0)
157149
speed_limits.angular = Vector3(x=0.0, y=0.0, z=1.0)
158-
deviation_limits = [1.0, 1.0, 1.0, 0.5, 1.0, 1.0, 1.0]
150+
deviation_limits = [1.0, 1.0, 1.0, 1.0, 1.0, 1.0]
159151

160152
# specify damping and gain scaling
161153
damping_factor = 0.1
@@ -168,7 +160,7 @@ def test_force_mode_controller(self, tf_prefix):
168160
trans_before = self.tf_buffer.lookup_transform(
169161
tf_prefix + "base", tf_prefix + "tool0", rclpy.time.Time()
170162
)
171-
except TransformException as ex:
163+
except TransformException:
172164
pass
173165

174166
# Send request to controller
@@ -199,17 +191,15 @@ def test_force_mode_controller(self, tf_prefix):
199191
trans_after = self.tf_buffer.lookup_transform(
200192
tf_prefix + "base", tf_prefix + "tool0", timepoint
201193
)
202-
except TransformException as ex:
194+
except TransformException:
203195
pass
204196

205197
# task frame and wrench determines the expected motion
206198
# In the example we used
207199
# - a task frame rotated pi/2 deg around the base frame's x axis
208200
# - a wrench with a positive z component for the force
209201
# => we should expect a motion in negative y of the base frame
210-
self.assertTrue(
211-
trans_after.transform.translation.y < trans_before.transform.translation.y
212-
)
202+
self.assertTrue(trans_after.transform.translation.y < trans_before.transform.translation.y)
213203
self.assertAlmostEqual(
214204
trans_after.transform.translation.x,
215205
trans_before.transform.translation.x,

0 commit comments

Comments
 (0)