Skip to content

Commit 99524bd

Browse files
style(pre-commit): autofix
1 parent f62a230 commit 99524bd

File tree

7 files changed

+28
-26
lines changed

7 files changed

+28
-26
lines changed

localization/aw_pose_covariance_modifier_node/CMakeLists.txt

+1-1
Original file line numberDiff line numberDiff line change
@@ -29,4 +29,4 @@ include_directories(src/include/)
2929

3030

3131
ament_auto_package(INSTALL_TO_SHARE
32-
launch)
32+
launch)

localization/aw_pose_covariance_modifier_node/package.xml

+2-2
Original file line numberDiff line numberDiff line change
@@ -15,11 +15,11 @@
1515
<build_depend>rosidl_default_generators</build_depend>
1616

1717
<depend>geometry_msgs</depend>
18+
<depend>rcl_interfaces</depend>
1819
<depend>rclcpp</depend>
1920
<depend>rclcpp_components</depend>
20-
<depend>rcl_interfaces</depend>
2121

2222
<export>
2323
<build_type>ament_cmake</build_type>
2424
</export>
25-
</package>
25+
</package>

localization/aw_pose_covariance_modifier_node/src/aw_pose_covariance_modifier_node.cpp

+12-12
Original file line numberDiff line numberDiff line change
@@ -28,27 +28,23 @@ AWPoseCovarianceModifierNode::AWPoseCovarianceModifierNode() : Node("AWPoseCovar
2828
new_pose_estimator_pub_ = this->create_publisher<geometry_msgs::msg::PoseWithCovarianceStamped>(
2929
"output_pose_with_covariance_topic", 10);
3030

31-
client_ =
32-
this->create_client<rcl_interfaces::srv::SetParameters>("/localization/pose_estimator/ndt_scan_matcher/set_parameters");
31+
client_ = this->create_client<rcl_interfaces::srv::SetParameters>(
32+
"/localization/pose_estimator/ndt_scan_matcher/set_parameters");
3333

3434
while (!client_->wait_for_service(std::chrono::seconds(1)) && rclcpp::ok()) {
35-
RCLCPP_INFO(
36-
this->get_logger(),
37-
"Waiting for aw_pose_covariance_modifier_node service...");
35+
RCLCPP_INFO(this->get_logger(), "Waiting for aw_pose_covariance_modifier_node service...");
3836
}
3937

4038
activateNDTCovModifier = AWPoseCovarianceModifierNode::callNDTCovarianceModifier();
4139
if (activateNDTCovModifier == 1) {
4240
RCLCPP_INFO(get_logger(), "NDT pose covariance modifier activated ...");
43-
}
44-
else{
41+
} else {
4542
RCLCPP_WARN(get_logger(), "Failed to enable NDT pose covariance modifier ...");
4643
}
4744
}
4845

4946
bool AWPoseCovarianceModifierNode::callNDTCovarianceModifier()
5047
{
51-
5248
auto request = std::make_shared<rcl_interfaces::srv::SetParameters::Request>();
5349

5450
rcl_interfaces::msg::Parameter parameter;
@@ -66,14 +62,18 @@ bool AWPoseCovarianceModifierNode::callNDTCovarianceModifier()
6662
auto response = result_.get();
6763

6864
if (response && response->results.data()) {
69-
RCLCPP_INFO(this->get_logger(), "aw_pose_covariance_modifier.enable parameter set successfully.");
65+
RCLCPP_INFO(
66+
this->get_logger(), "aw_pose_covariance_modifier.enable parameter set successfully.");
7067
return true;
7168
} else {
72-
RCLCPP_ERROR(this->get_logger(), "An error occurred while setting the aw_pose_covariance_modifier.enable parameter.");
69+
RCLCPP_ERROR(
70+
this->get_logger(),
71+
"An error occurred while setting the aw_pose_covariance_modifier.enable parameter.");
7372
return false;
7473
}
7574
} else {
76-
RCLCPP_ERROR(this->get_logger(), "The request was not completed within the specified time.");
75+
RCLCPP_ERROR(
76+
this->get_logger(), "The request was not completed within the specified time.");
7777
return false;
7878
}
7979
});
@@ -109,4 +109,4 @@ int main(int argc, char * argv[])
109109
rclcpp::spin(std::make_shared<AWPoseCovarianceModifierNode>());
110110
rclcpp::shutdown();
111111
return 0;
112-
}
112+
}

localization/aw_pose_covariance_modifier_node/src/include/aw_pose_covariance_modifier_node.hpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -14,10 +14,11 @@
1414
#ifndef AW_POSE_COVARIANCE_MODIFIER_NODE_HPP_
1515
#define AW_POSE_COVARIANCE_MODIFIER_NODE_HPP_
1616

17+
#include <rcl_interfaces/srv/set_parameters.hpp>
1718
#include <rclcpp/rclcpp.hpp>
1819

1920
#include <geometry_msgs/msg/pose_with_covariance_stamped.hpp>
20-
#include <rcl_interfaces/srv/set_parameters.hpp>
21+
2122
#include <string>
2223

2324
class AWPoseCovarianceModifierNode : public rclcpp::Node
@@ -41,4 +42,4 @@ class AWPoseCovarianceModifierNode : public rclcpp::Node
4142
bool activateNDTCovModifier = 0;
4243
};
4344

44-
#endif // AW_POSE_COVARIANCE_MODIFIER_NODE_HPP_
45+
#endif // AW_POSE_COVARIANCE_MODIFIER_NODE_HPP_

localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@
2020
#include "localization_util/smart_pose_buffer.hpp"
2121
#include "ndt_scan_matcher/hyper_parameters.hpp"
2222
#include "ndt_scan_matcher/map_update_module.hpp"
23+
#include "rcl_interfaces/srv/set_parameters.hpp"
2324

2425
#include <rclcpp/rclcpp.hpp>
2526
#include <tier4_autoware_utils/ros/logger_level_configure.hpp>
@@ -42,7 +43,6 @@
4243
#include <tf2/transform_datatypes.h>
4344
#include <tf2_ros/buffer.h>
4445
#include <tf2_ros/transform_listener.h>
45-
#include "rcl_interfaces/srv/set_parameters.hpp"
4646

4747
#ifdef ROS_DISTRO_GALACTIC
4848
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>

localization/ndt_scan_matcher/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,7 @@
2828
<depend>nav_msgs</depend>
2929
<depend>ndt_omp</depend>
3030
<depend>pcl_conversions</depend>
31+
<depend>rcl_interfaces</depend>
3132
<depend>rclcpp</depend>
3233
<depend>sensor_msgs</depend>
3334
<depend>std_msgs</depend>
@@ -42,7 +43,6 @@
4243
<depend>tier4_localization_msgs</depend>
4344
<depend>tree_structured_parzen_estimator</depend>
4445
<depend>visualization_msgs</depend>
45-
<depend>rcl_interfaces</depend>
4646

4747
<test_depend>ament_cmake_cppcheck</test_depend>
4848
<test_depend>ament_lint_auto</test_depend>

localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp

+8-7
Original file line numberDiff line numberDiff line change
@@ -198,12 +198,12 @@ void NDTScanMatcher::setParametersCallback(
198198
{
199199
std::lock_guard<std::mutex> lock(mutex_cov_modifier_);
200200

201-
for (const auto &param : request->parameters) {
202-
203-
if(param.name == "aw_pose_covariance_modifier.enable"){
204-
201+
for (const auto & param : request->parameters) {
202+
if (param.name == "aw_pose_covariance_modifier.enable") {
205203
activate_pose_covariance_modifier_ = param.value.bool_value;
206-
RCLCPP_INFO(this->get_logger(), "aw_pose_covariance_modifier.enable set to : %d", activate_pose_covariance_modifier_);
204+
RCLCPP_INFO(
205+
this->get_logger(), "aw_pose_covariance_modifier.enable set to : %d",
206+
activate_pose_covariance_modifier_);
207207

208208
rcl_interfaces::msg::SetParametersResult result;
209209
result.successful = true;
@@ -213,11 +213,12 @@ void NDTScanMatcher::setParametersCallback(
213213
}
214214
}
215215

216-
if(activate_pose_covariance_modifier_ == 1){
216+
if (activate_pose_covariance_modifier_ == 1) {
217217
NDTScanMatcher::createTrustedSourcePoseSubscriber();
218218
}
219219
}
220-
void NDTScanMatcher::createTrustedSourcePoseSubscriber(){
220+
void NDTScanMatcher::createTrustedSourcePoseSubscriber()
221+
{
221222
trusted_source_pose_sub_ =
222223
this->create_subscription<geometry_msgs::msg::PoseWithCovarianceStamped>(
223224
"input_trusted_pose_topic", 100,

0 commit comments

Comments
 (0)