Skip to content

Commit 91c7785

Browse files
committed
Fixing with pre-commit
1 parent c326ba7 commit 91c7785

File tree

1 file changed

+11
-12
lines changed

1 file changed

+11
-12
lines changed

force_torque_sensor_broadcaster/src/force_torque_sensor_broadcaster.cpp

Lines changed: 11 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -20,9 +20,9 @@
2020

2121
#include <limits>
2222
#include <memory>
23-
#include <rclcpp/logging.hpp>
2423
#include <string>
2524

25+
#include "rclcpp/logging.hpp"
2626
#include "tf2/utils.hpp"
2727
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
2828

@@ -99,21 +99,19 @@ controller_interface::CallbackReturn ForceTorqueSensorBroadcaster::on_configure(
9999
}
100100
catch (const std::exception & e)
101101
{
102-
fprintf(
103-
stderr,
104-
"Exception thrown during filter chain creation with message : %s \n",
105-
e.what());
102+
fprintf(stderr, "Exception thrown during filter chain creation with message : %s \n", e.what());
106103
return CallbackReturn::ERROR;
107104
}
108105

109-
// As the sensor_filter_chain parameter is of type 'none', we cannot directly check if it is present.
110-
// Even if the sensor_filter_chain parameter is not specified, the filter chain will be correctly
111-
// configured with an empty list of filters (https://github.com/ros/filters/issues/89).
106+
// As the sensor_filter_chain parameter is of type 'none', we cannot directly check if it is
107+
// present. Even if the sensor_filter_chain parameter is not specified, the filter chain will be
108+
// correctly configured with an empty list of filters (https://github.com/ros/filters/issues/89).
112109
has_filter_chain_ = filter_chain_->configure(
113110
"sensor_filter_chain", get_node()->get_node_logging_interface(),
114111
get_node()->get_node_parameters_interface());
115112

116-
RCLCPP_INFO_EXPRESSION(get_node()->get_logger(), has_filter_chain_, "Filter chain is successfully configured!");
113+
RCLCPP_INFO_EXPRESSION(
114+
get_node()->get_logger(), has_filter_chain_, "Filter chain is successfully configured!");
117115

118116
try
119117
{
@@ -124,7 +122,7 @@ controller_interface::CallbackReturn ForceTorqueSensorBroadcaster::on_configure(
124122

125123
sensor_filtered_state_publisher_ =
126124
get_node()->create_publisher<geometry_msgs::msg::WrenchStamped>(
127-
"~/wrench_filtered", rclcpp::SystemDefaultsQoS());
125+
"~/wrench_filtered", rclcpp::SystemDefaultsQoS());
128126
realtime_filtered_publisher_ =
129127
std::make_unique<StateRTPublisher>(sensor_filtered_state_publisher_);
130128
}
@@ -143,7 +141,8 @@ controller_interface::CallbackReturn ForceTorqueSensorBroadcaster::on_configure(
143141
realtime_raw_publisher_->msg_.header.frame_id = params_.frame_id;
144142
realtime_raw_publisher_->unlock();
145143

146-
if (has_filter_chain_){
144+
if (has_filter_chain_)
145+
{
147146
realtime_filtered_publisher_->lock();
148147
realtime_filtered_publisher_->msg_.header.frame_id = params_.frame_id;
149148
realtime_filtered_publisher_->unlock();
@@ -201,7 +200,7 @@ controller_interface::return_type ForceTorqueSensorBroadcaster::update_and_write
201200
realtime_raw_publisher_->unlockAndPublish();
202201
}
203202

204-
if(has_filter_chain_)
203+
if (has_filter_chain_)
205204
{
206205
// Filter sensor data, if no filter chain config was specified, wrench_filtered_ = wrench_raw_
207206
auto filtered = filter_chain_->update(wrench_raw_, wrench_filtered_);

0 commit comments

Comments
 (0)