Skip to content

Commit

Permalink
refactor(tier4_perception_rviz_plugin): apply clang-tidy (autowarefou…
Browse files Browse the repository at this point in the history
…ndation#1624)

* refactor(tier4_perception_rviz_plugin): apply clang-tidy

* ci(pre-commit): autofix

Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
  • Loading branch information
2 people authored and satoshi-ota committed Jan 17, 2023
1 parent d16b432 commit f4e5e2f
Show file tree
Hide file tree
Showing 10 changed files with 27 additions and 30 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ private Q_SLOTS:
void unsubscribe();
void processMessage(const geometry_msgs::msg::PoseStamped::ConstSharedPtr message);

private:
private: // NOLINT for Qt
void updateHistory();
void updateLines();

Expand Down
4 changes: 2 additions & 2 deletions common/tier4_perception_rviz_plugin/src/tools/car_pose.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -99,7 +99,7 @@ CarInitialPoseTool::CarInitialPoseTool()

void CarInitialPoseTool::onInitialize()
{
PoseTool::onInitialize();
rviz_plugins::InteractiveObjectTool::onInitialize();
setName("2D Dummy Car");
updateTopic();
}
Expand Down Expand Up @@ -184,7 +184,7 @@ BusInitialPoseTool::BusInitialPoseTool()

void BusInitialPoseTool::onInitialize()
{
PoseTool::onInitialize();
rviz_plugins::InteractiveObjectTool::onInitialize();
setName("2D Dummy Bus");
updateTopic();
}
Expand Down
8 changes: 4 additions & 4 deletions common/tier4_perception_rviz_plugin/src/tools/car_pose.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,16 +61,16 @@ class CarInitialPoseTool : public InteractiveObjectTool
{
public:
CarInitialPoseTool();
void onInitialize();
Object createObjectMsg() const override;
void onInitialize() override;
[[nodiscard]] Object createObjectMsg() const override;
};

class BusInitialPoseTool : public InteractiveObjectTool
{
public:
BusInitialPoseTool();
void onInitialize();
Object createObjectMsg() const override;
void onInitialize() override;
[[nodiscard]] Object createObjectMsg() const override;
};

} // namespace rviz_plugins
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -67,16 +67,15 @@ class DeleteAllObjectsTool : public rviz_default_plugins::tools::PoseTool

public:
DeleteAllObjectsTool();
virtual ~DeleteAllObjectsTool() {}
virtual void onInitialize();
void onInitialize() override;

protected:
virtual void onPoseSet(double x, double y, double theta);
void onPoseSet(double x, double y, double theta) override;

private Q_SLOTS:
void updateTopic();

private:
private: // NOLINT for Qt
rclcpp::Clock::SharedPtr clock_;
rclcpp::Publisher<dummy_perception_publisher::msg::Object>::SharedPtr dummy_object_info_pub_;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,6 @@ InteractiveObject::InteractiveObject(const Ogre::Vector3 & point)
{
velocity_ = Ogre::Vector3::ZERO;
point_ = point;
theta_ = 0.0;

std::mt19937 gen(std::random_device{}());
std::independent_bits_engine<std::mt19937, 8, uint8_t> bit_eng(gen);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -89,35 +89,35 @@ class InteractiveObject
{
public:
explicit InteractiveObject(const Ogre::Vector3 & point);
~InteractiveObject() {}

std::array<uint8_t, 16> uuid() const;
[[nodiscard]] std::array<uint8_t, 16> uuid() const;
void twist(geometry_msgs::msg::Twist & twist) const;
void transform(tf2::Transform & tf_map2object) const;
void update(const Ogre::Vector3 & point);
void reset();
double distance(const Ogre::Vector3 & point);

private:
std::array<uint8_t, 16> uuid_;
std::array<uint8_t, 16> uuid_{};
Ogre::Vector3 point_;
Ogre::Vector3 velocity_;
double theta_;
double theta_{0.0};
};

class InteractiveObjectCollection
{
public:
InteractiveObjectCollection();
~InteractiveObjectCollection() {}

void select(const Ogre::Vector3 & point);
boost::optional<std::array<uint8_t, 16>> reset();
boost::optional<std::array<uint8_t, 16>> create(const Ogre::Vector3 & point);
boost::optional<std::array<uint8_t, 16>> remove(const Ogre::Vector3 & point);
boost::optional<std::array<uint8_t, 16>> update(const Ogre::Vector3 & point);
boost::optional<geometry_msgs::msg::Twist> twist(const std::array<uint8_t, 16> & uuid) const;
boost::optional<tf2::Transform> transform(const std::array<uint8_t, 16> & uuid) const;
[[nodiscard]] boost::optional<geometry_msgs::msg::Twist> twist(
const std::array<uint8_t, 16> & uuid) const;
[[nodiscard]] boost::optional<tf2::Transform> transform(
const std::array<uint8_t, 16> & uuid) const;

private:
size_t nearest(const Ogre::Vector3 & point);
Expand All @@ -130,17 +130,16 @@ class InteractiveObjectTool : public rviz_default_plugins::tools::PoseTool
Q_OBJECT

public:
virtual ~InteractiveObjectTool() = default;
virtual void onInitialize();
void onInitialize() override;
int processMouseEvent(rviz_common::ViewportMouseEvent & event) override;
int processKeyEvent(QKeyEvent * event, rviz_common::RenderPanel * panel) override;

virtual Object createObjectMsg() const = 0;
[[nodiscard]] virtual Object createObjectMsg() const = 0;

protected Q_SLOTS:
virtual void updateTopic();

protected:
protected: // NOLINT for Qt
rclcpp::Clock::SharedPtr clock_;
rclcpp::Publisher<Object>::SharedPtr dummy_object_info_pub_;

Expand All @@ -161,7 +160,7 @@ protected Q_SLOTS:

private:
void publishObjectMsg(const std::array<uint8_t, 16> & uuid, const uint32_t action);
void onPoseSet(double x, double y, double theta);
void onPoseSet(double x, double y, double theta) override;

InteractiveObjectCollection objects_;
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -93,7 +93,7 @@ PedestrianInitialPoseTool::PedestrianInitialPoseTool()

void PedestrianInitialPoseTool::onInitialize()
{
PoseTool::onInitialize();
rviz_plugins::InteractiveObjectTool::onInitialize();
setName("2D Dummy Pedestrian");
updateTopic();
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -61,8 +61,8 @@ class PedestrianInitialPoseTool : public InteractiveObjectTool
{
public:
PedestrianInitialPoseTool();
void onInitialize();
Object createObjectMsg() const override;
void onInitialize() override;
[[nodiscard]] Object createObjectMsg() const override;
};

} // namespace rviz_plugins
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,7 @@ UnknownInitialPoseTool::UnknownInitialPoseTool()

void UnknownInitialPoseTool::onInitialize()
{
PoseTool::onInitialize();
rviz_plugins::InteractiveObjectTool::onInitialize();
setName("2D Dummy Unknown");
updateTopic();
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,8 +56,8 @@ class UnknownInitialPoseTool : public InteractiveObjectTool
{
public:
UnknownInitialPoseTool();
void onInitialize();
Object createObjectMsg() const override;
void onInitialize() override;
[[nodiscard]] Object createObjectMsg() const override;
};

} // namespace rviz_plugins
Expand Down

0 comments on commit f4e5e2f

Please sign in to comment.