Skip to content

Commit a85c67b

Browse files
authored
fix(autoware_radar_fusion_to_detected_object): fix bugprone-errors (#9654)
fix: bugprone-error Signed-off-by: kobayu858 <yutaro.kobayashi@tier4.jp>
1 parent 932e87f commit a85c67b

File tree

2 files changed

+5
-9
lines changed

2 files changed

+5
-9
lines changed

perception/autoware_radar_fusion_to_detected_object/src/node.cpp

+4-6
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,6 @@ using namespace std::literals;
2525
using std::chrono::duration;
2626
using std::chrono::duration_cast;
2727
using std::chrono::nanoseconds;
28-
using std::placeholders::_1;
2928

3029
namespace
3130
{
@@ -58,7 +57,7 @@ RadarObjectFusionToDetectedObjectNode::RadarObjectFusionToDetectedObjectNode(
5857
{
5958
// Parameter Server
6059
set_param_res_ = this->add_on_set_parameters_callback(
61-
std::bind(&RadarObjectFusionToDetectedObjectNode::onSetParam, this, _1));
60+
std::bind(&RadarObjectFusionToDetectedObjectNode::onSetParam, this, std::placeholders::_1));
6261

6362
// Node Parameter
6463
node_param_.update_rate_hz = declare_parameter<double>("node_params.update_rate_hz");
@@ -93,11 +92,10 @@ RadarObjectFusionToDetectedObjectNode::RadarObjectFusionToDetectedObjectNode(
9392
sub_object_.subscribe(this, "~/input/objects", rclcpp::QoS{1}.get_rmw_qos_profile());
9493
sub_radar_.subscribe(this, "~/input/radars", rclcpp::QoS{1}.get_rmw_qos_profile());
9594

96-
using std::placeholders::_1;
97-
using std::placeholders::_2;
9895
sync_ptr_ = std::make_shared<Sync>(SyncPolicy(20), sub_object_, sub_radar_);
99-
sync_ptr_->registerCallback(
100-
std::bind(&RadarObjectFusionToDetectedObjectNode::onData, this, _1, _2));
96+
sync_ptr_->registerCallback(std::bind(
97+
&RadarObjectFusionToDetectedObjectNode::onData, this, std::placeholders::_1,
98+
std::placeholders::_2));
10199

102100
// Publisher
103101
pub_objects_ = create_publisher<DetectedObjects>("~/output/objects", 1);

perception/autoware_radar_fusion_to_detected_object/src/radar_fusion_to_detected_object.cpp

+1-3
Original file line numberDiff line numberDiff line change
@@ -158,9 +158,7 @@ bool RadarFusionToDetectedObject::isYawCorrect(
158158
const double object_yaw = autoware::universe_utils::normalizeRadian(
159159
tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation));
160160
const double diff_yaw = autoware::universe_utils::normalizeRadian(twist_yaw - object_yaw);
161-
if (std::abs(diff_yaw) < yaw_threshold) {
162-
return true;
163-
} else if (M_PI - yaw_threshold < std::abs(diff_yaw)) {
161+
if (std::abs(diff_yaw) < yaw_threshold || M_PI - yaw_threshold < std::abs(diff_yaw)) {
164162
return true;
165163
} else {
166164
return false;

0 commit comments

Comments
 (0)