@@ -28,27 +28,23 @@ AWPoseCovarianceModifierNode::AWPoseCovarianceModifierNode() : Node("AWPoseCovar
28
28
new_pose_estimator_pub_ = this ->create_publisher <geometry_msgs::msg::PoseWithCovarianceStamped>(
29
29
" output_pose_with_covariance_topic" , 10 );
30
30
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" );
33
33
34
34
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..." );
38
36
}
39
37
40
38
activateNDTCovModifier = AWPoseCovarianceModifierNode::callNDTCovarianceModifier ();
41
39
if (activateNDTCovModifier == 1 ) {
42
40
RCLCPP_INFO (get_logger (), " NDT pose covariance modifier activated ..." );
43
- }
44
- else {
41
+ } else {
45
42
RCLCPP_WARN (get_logger (), " Failed to enable NDT pose covariance modifier ..." );
46
43
}
47
44
}
48
45
49
46
bool AWPoseCovarianceModifierNode::callNDTCovarianceModifier ()
50
47
{
51
-
52
48
auto request = std::make_shared<rcl_interfaces::srv::SetParameters::Request>();
53
49
54
50
rcl_interfaces::msg::Parameter parameter;
@@ -66,14 +62,18 @@ bool AWPoseCovarianceModifierNode::callNDTCovarianceModifier()
66
62
auto response = result_.get ();
67
63
68
64
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." );
70
67
return true ;
71
68
} 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." );
73
72
return false ;
74
73
}
75
74
} 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." );
77
77
return false ;
78
78
}
79
79
});
@@ -109,4 +109,4 @@ int main(int argc, char * argv[])
109
109
rclcpp::spin (std::make_shared<AWPoseCovarianceModifierNode>());
110
110
rclcpp::shutdown ();
111
111
return 0 ;
112
- }
112
+ }
0 commit comments