Skip to content

Commit

Permalink
fix(autoware_stop_filter): fix bugprone-reserved-identifier (#9643)
Browse files Browse the repository at this point in the history
* fix: bugprone-reserved-identifier

Signed-off-by: kobayu858 <[email protected]>

* fix: fmt

Signed-off-by: kobayu858 <[email protected]>

---------

Signed-off-by: kobayu858 <[email protected]>
  • Loading branch information
kobayu858 authored Dec 13, 2024
1 parent fee8fe5 commit 9ff1c38
Showing 1 changed file with 1 addition and 3 deletions.
4 changes: 1 addition & 3 deletions localization/autoware_stop_filter/src/stop_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,6 @@
#include <string>
#include <utility>

using std::placeholders::_1;

namespace autoware::stop_filter
{
StopFilter::StopFilter(const rclcpp::NodeOptions & node_options)
Expand All @@ -33,7 +31,7 @@ StopFilter::StopFilter(const rclcpp::NodeOptions & node_options)
wz_threshold_ = declare_parameter<double>("wz_threshold");

sub_odom_ = create_subscription<nav_msgs::msg::Odometry>(
"input/odom", 1, std::bind(&StopFilter::callback_odometry, this, _1));
"input/odom", 1, std::bind(&StopFilter::callback_odometry, this, std::placeholders::_1));

pub_odom_ = create_publisher<nav_msgs::msg::Odometry>("output/odom", 1);
pub_stop_flag_ = create_publisher<tier4_debug_msgs::msg::BoolStamped>("debug/stop_flag", 1);
Expand Down

0 comments on commit 9ff1c38

Please sign in to comment.