Skip to content

Commit

Permalink
style(pre-commit): autofix
Browse files Browse the repository at this point in the history
  • Loading branch information
pre-commit-ci[bot] committed Jun 13, 2024
1 parent 45c993f commit 2e6a3ed
Show file tree
Hide file tree
Showing 9 changed files with 24 additions and 21 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -16,15 +16,15 @@

#include "pose_estimator_arbiter/rule_helper/grid_key.hpp"

#include <boost/functional/hash.hpp>

#include <pcl_conversions/pcl_conversions.h>

#include <memory>
#include <string>
#include <unordered_map>
#include <vector>

#include <boost/functional/hash.hpp>

#include <pcl_conversions/pcl_conversions.h>

namespace pose_estimator_arbiter::rule_helper
{
PcdOccupancy::PcdOccupancy(int pcd_density_upper_threshold, int pcd_density_lower_threshold)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,6 @@
#ifndef POSE_ESTIMATOR_ARBITER__RULE_HELPER__PCD_OCCUPANCY_HPP_
#define POSE_ESTIMATOR_ARBITER__RULE_HELPER__PCD_OCCUPANCY_HPP_

#include <string>

#include <rclcpp/node.hpp>

#include <sensor_msgs/msg/point_cloud2.hpp>
Expand All @@ -26,6 +24,8 @@
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>

#include <string>

namespace pose_estimator_arbiter::rule_helper
{
class PcdOccupancy
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ using BoostPolygon = boost::geometry::model::polygon<BoostPoint>;

struct PoseEstimatorArea::Impl
{
explicit Impl(const rclcpp::Logger& logger) : logger_(logger) {}
explicit Impl(const rclcpp::Logger & logger) : logger_(logger) {}
std::multimap<std::string, BoostPolygon> bounding_boxes_;

void init(HADMapBin::ConstSharedPtr msg);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,8 @@ namespace pose_estimator_arbiter::switch_rule
PcdMapBasedRule::PcdMapBasedRule(
rclcpp::Node & node, std::unordered_set<PoseEstimatorType> running_estimator_list,
std::shared_ptr<const SharedData> shared_data)
: BaseSwitchRule(node), running_estimator_list_(std::move(running_estimator_list)),
: BaseSwitchRule(node),
running_estimator_list_(std::move(running_estimator_list)),
shared_data_(std::move(shared_data))
{
const int pcd_density_upper_threshold =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,8 @@ namespace pose_estimator_arbiter::switch_rule
VectorMapBasedRule::VectorMapBasedRule(
rclcpp::Node & node, std::unordered_set<PoseEstimatorType> running_estimator_list,
std::shared_ptr<const SharedData> shared_data)
: BaseSwitchRule(node), running_estimator_list_(std::move(running_estimator_list)),
: BaseSwitchRule(node),
running_estimator_list_(std::move(running_estimator_list)),
shared_data_(std::move(shared_data))
{
pose_estimator_area_ = std::make_unique<rule_helper::PoseEstimatorArea>(node.get_logger());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,10 +35,10 @@ class BaseStopper
}

virtual ~BaseStopper() = default;
BaseStopper(const BaseStopper& other) = default;
BaseStopper(BaseStopper&& other) noexcept = default;
BaseStopper& operator=(const BaseStopper& other) = default;
BaseStopper& operator=(BaseStopper&& other) noexcept = default;
BaseStopper(const BaseStopper & other) = default;
BaseStopper(BaseStopper && other) noexcept = default;
BaseStopper & operator=(const BaseStopper & other) = default;
BaseStopper & operator=(BaseStopper && other) noexcept = default;
void enable() { set_enable(true); }
void disable() { set_enable(false); }

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,8 @@ class StopperArTag : public BaseStopper
using SetBool = std_srvs::srv::SetBool;

public:
explicit StopperArTag(rclcpp::Node * node,
const std::shared_ptr<const SharedData> & shared_data) : BaseStopper(node, shared_data)
explicit StopperArTag(rclcpp::Node * node, const std::shared_ptr<const SharedData> & shared_data)
: BaseStopper(node, shared_data)
{
ar_tag_is_enabled_ = true;
pub_image_ = node->create_publisher<Image>("~/output/artag/image", rclcpp::SensorDataQoS());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,9 @@ class StopperEagleye : public BaseStopper
using PoseCovStamped = geometry_msgs::msg::PoseWithCovarianceStamped;

public:
explicit StopperEagleye(rclcpp::Node * node,
const std::shared_ptr<const SharedData> & shared_data) : BaseStopper(node, shared_data)
explicit StopperEagleye(
rclcpp::Node * node, const std::shared_ptr<const SharedData> & shared_data)
: BaseStopper(node, shared_data)
{
eagleye_is_enabled_ = true;
pub_pose_ = node->create_publisher<PoseCovStamped>("~/output/eagleye/pose_with_covariance", 5);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,10 +40,10 @@ class BaseSwitchRule
}

virtual ~BaseSwitchRule() = default;
BaseSwitchRule(const BaseSwitchRule& other) = default;
BaseSwitchRule(BaseSwitchRule&& other) noexcept = default;
BaseSwitchRule& operator=(const BaseSwitchRule& other) = default;
BaseSwitchRule& operator=(BaseSwitchRule&& other) noexcept = default;
BaseSwitchRule(const BaseSwitchRule & other) = default;
BaseSwitchRule(BaseSwitchRule && other) noexcept = default;
BaseSwitchRule & operator=(const BaseSwitchRule & other) = default;
BaseSwitchRule & operator=(BaseSwitchRule && other) noexcept = default;
virtual std::unordered_map<PoseEstimatorType, bool> update() = 0;
virtual std::string debug_string() { return std::string{}; }
virtual MarkerArray debug_marker_array() { return MarkerArray{}; }
Expand Down

0 comments on commit 2e6a3ed

Please sign in to comment.