WATANABE Aoi 2023-07-05
Merge pull request #33 from HarvestX/fix/macro-place
Fix macro place
@2db79bb9adbfd6e6f9faf45c3feb836658742ebc
p9n_example/include/p9n_example/display_node.hpp
--- p9n_example/include/p9n_example/display_node.hpp
+++ p9n_example/include/p9n_example/display_node.hpp
@@ -16,11 +16,10 @@
 
 #include <string>
 #include <memory>
-#include <sensor_msgs/msg/joy.hpp>
-#include <rclcpp/rclcpp.hpp>
 
 #include <p9n_interface/p9n_interface.hpp>
-
+#include <rclcpp/rclcpp.hpp>
+#include <sensor_msgs/msg/joy.hpp>
 
 namespace p9n_example
 {
@@ -37,6 +36,3 @@
   void onJoy(sensor_msgs::msg::Joy::ConstSharedPtr);
 };
 }  // namespace p9n_example
-
-#include "rclcpp_components/register_node_macro.hpp"
-RCLCPP_COMPONENTS_REGISTER_NODE(p9n_example::DisplayNode)
p9n_example/src/display_node.cpp
--- p9n_example/src/display_node.cpp
+++ p9n_example/src/display_node.cpp
@@ -21,7 +21,6 @@
 DisplayNode::DisplayNode(const rclcpp::NodeOptions & options)
 : rclcpp::Node("display_node", options)
 {
-
   const std::string hw_name = this->declare_parameter<std::string>(
     "hw_type", p9n_interface::HW_NAME::DUALSENSE);
 
@@ -162,8 +161,11 @@
   }
 
   if (this->p9n_if_->pressedAny()) {
-    using namespace std::chrono_literals;
+    using namespace std::chrono_literals;  // NOLINT
     rclcpp::sleep_for(200ms);
   }
 }
 }  // namespace p9n_example
+
+#include "rclcpp_components/register_node_macro.hpp"
+RCLCPP_COMPONENTS_REGISTER_NODE(p9n_example::DisplayNode)
p9n_node/include/p9n_node/teleop_twist_joy_node.hpp
--- p9n_node/include/p9n_node/teleop_twist_joy_node.hpp
+++ p9n_node/include/p9n_node/teleop_twist_joy_node.hpp
@@ -50,6 +50,3 @@
   void onWatchdog();
 };
 }  // namespace p9n_node
-
-#include "rclcpp_components/register_node_macro.hpp"
-RCLCPP_COMPONENTS_REGISTER_NODE(p9n_node::TeleopTwistJoyNode)
p9n_node/src/teleop_twist_joy_node.cpp
--- p9n_node/src/teleop_twist_joy_node.cpp
+++ p9n_node/src/teleop_twist_joy_node.cpp
@@ -92,3 +92,6 @@
   this->timer_watchdog_->cancel();
 }
 }  // namespace p9n_node
+
+#include "rclcpp_components/register_node_macro.hpp"
+RCLCPP_COMPONENTS_REGISTER_NODE(p9n_node::TeleopTwistJoyNode)
p9n_test/include/p9n_test/p9n_test_node.hpp
--- p9n_test/include/p9n_test/p9n_test_node.hpp
+++ p9n_test/include/p9n_test/p9n_test_node.hpp
@@ -39,9 +39,5 @@
 public:
   explicit PlayStationTestNode(const rclcpp::NodeOptions &);
   void onJoy(sensor_msgs::msg::Joy::ConstSharedPtr);
-
 };
 }  // namespace p9n_test
-
-#include "rclcpp_components/register_node_macro.hpp"
-RCLCPP_COMPONENTS_REGISTER_NODE(p9n_test::PlayStationTestNode)
p9n_test/src/p9n_test_node.cpp
--- p9n_test/src/p9n_test_node.cpp
+++ p9n_test/src/p9n_test_node.cpp
@@ -100,7 +100,6 @@
     }
   }
 
-
   if (this->wf_handler_->isDone()) {
     RCLCPP_INFO(this->get_logger(), "Done!");
     this->wf_handler_->showResult();
@@ -109,9 +108,12 @@
   }
 
   // Delay for button chattering
-  using namespace std::chrono_literals;
+  using namespace std::chrono_literals;  // NOLINT
   rclcpp::sleep_for(500ms);
 }
 
 
 }  // namespace p9n_test
+
+#include "rclcpp_components/register_node_macro.hpp"
+RCLCPP_COMPONENTS_REGISTER_NODE(p9n_test::PlayStationTestNode)
Add a comment
List