Skip to content

Commit

Permalink
fix(autoware_radar_fusion_to_detected_object): fix bugprone-errors (#…
Browse files Browse the repository at this point in the history
…9654)

fix: bugprone-error

Signed-off-by: kobayu858 <[email protected]>
  • Loading branch information
kobayu858 authored Dec 16, 2024
1 parent 932e87f commit a85c67b
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 9 deletions.
10 changes: 4 additions & 6 deletions perception/autoware_radar_fusion_to_detected_object/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,6 @@ using namespace std::literals;
using std::chrono::duration;
using std::chrono::duration_cast;
using std::chrono::nanoseconds;
using std::placeholders::_1;

namespace
{
Expand Down Expand Up @@ -58,7 +57,7 @@ RadarObjectFusionToDetectedObjectNode::RadarObjectFusionToDetectedObjectNode(
{
// Parameter Server
set_param_res_ = this->add_on_set_parameters_callback(
std::bind(&RadarObjectFusionToDetectedObjectNode::onSetParam, this, _1));
std::bind(&RadarObjectFusionToDetectedObjectNode::onSetParam, this, std::placeholders::_1));

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

using std::placeholders::_1;
using std::placeholders::_2;
sync_ptr_ = std::make_shared<Sync>(SyncPolicy(20), sub_object_, sub_radar_);
sync_ptr_->registerCallback(
std::bind(&RadarObjectFusionToDetectedObjectNode::onData, this, _1, _2));
sync_ptr_->registerCallback(std::bind(
&RadarObjectFusionToDetectedObjectNode::onData, this, std::placeholders::_1,
std::placeholders::_2));

// Publisher
pub_objects_ = create_publisher<DetectedObjects>("~/output/objects", 1);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -158,9 +158,7 @@ bool RadarFusionToDetectedObject::isYawCorrect(
const double object_yaw = autoware::universe_utils::normalizeRadian(
tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation));
const double diff_yaw = autoware::universe_utils::normalizeRadian(twist_yaw - object_yaw);
if (std::abs(diff_yaw) < yaw_threshold) {
return true;
} else if (M_PI - yaw_threshold < std::abs(diff_yaw)) {
if (std::abs(diff_yaw) < yaw_threshold || M_PI - yaw_threshold < std::abs(diff_yaw)) {
return true;
} else {
return false;
Expand Down

0 comments on commit a85c67b

Please sign in to comment.