윤영준 윤영준 2024-12-09
README
@1f6b880ffb5b003a23b92b9fa77328d4f6184bac
README.md
--- README.md
+++ README.md
@@ -1,4 +1,19 @@
+# 원본으로부터 특기할만한 변경점 
+
+## `p9n_example` 에서의 변경점
+
+기존에는 단순히 플레이스테이션 컨트롤러의 입력을 받아 출력하는 역할만 있었으나, 이를 publish 할 수 있는 능력 부여
+
+또한, 동시 키 입력 지원 (기존 코드는 모든 인풋에 대하여 if else 로 switch 하는 방식이었으나 수정된 코드는 이를 개별로 처리하고 publish)
+
+이 외에도 `CmakeList.txt`, `package.xml` 파일의 스크립트간 의존관계 변경에 따른 수정 
+
+또한 이를 통하여 python 상에서 플레이스테이션 컨트롤러의 입력을 처리 할 수 있도록 joy_feed_back_receiver.py 예제 추가
+
+p9n_example 폴더내부의 cpp 코드, include hpp 코드, 모두 수정되었음.
+
 # PlayStation-JoyInterface-ROS2
+
 PlayStation Joy Controller Interface Package for ROS2.
 
 
p9n_example/CMakeLists.txt
--- p9n_example/CMakeLists.txt
+++ p9n_example/CMakeLists.txt
@@ -27,4 +27,12 @@
   ament_lint_auto_find_test_dependencies()
 endif()
 
+# ===========python node ============
+# Install Python scripts
+install(
+  PROGRAMS
+    scripts/joy_feedback_receiver.py
+  DESTINATION lib/${PROJECT_NAME}
+)
+
 ament_auto_package(INSTALL_TO_SHARE launch)
p9n_example/include/p9n_example/display_node.hpp
--- p9n_example/include/p9n_example/display_node.hpp
+++ p9n_example/include/p9n_example/display_node.hpp
@@ -20,6 +20,7 @@
 #include <p9n_interface/p9n_interface.hpp>
 #include <rclcpp/rclcpp.hpp>
 #include <sensor_msgs/msg/joy.hpp>
+#include <std_msgs/msg/string.hpp>
 
 namespace p9n_example
 {
@@ -30,6 +31,7 @@
   std::unique_ptr<p9n_interface::PlayStationInterface> p9n_if_;
 
   rclcpp::Subscription<sensor_msgs::msg::Joy>::SharedPtr joy_sub_;
+  rclcpp::Publisher<std_msgs::msg::String>::SharedPtr feedback_pub_;
 
 public:
   explicit DisplayNode(const rclcpp::NodeOptions &);
p9n_example/package.xml
--- p9n_example/package.xml
+++ p9n_example/package.xml
@@ -12,6 +12,9 @@
   <depend>rclcpp_components</depend>
   <depend>p9n_interface</depend>
   <exec_depend>joy</exec_depend>
+  
+  <exec_depend>python3</exec_depend>
+  <exec_depend>setuptools</exec_depend>
 
   <test_depend>ament_lint_auto</test_depend>
   <test_depend>ament_lint_common</test_depend>
 
p9n_example/scripts/joy_feedback_receiver.py (added)
+++ p9n_example/scripts/joy_feedback_receiver.py
@@ -0,0 +1,36 @@
+#!/usr/bin/env python3
+# shebang line for directing correct python executables. ROS2 uses system python installation, not conda.
+import rclpy
+from rclpy.node import Node
+from std_msgs.msg import String
+
+class JoyFeedbackReceiver(Node):
+    def __init__(self):
+        super().__init__('joy_feedback_receiver')
+        # Create a subscription to the 'joy_feedback' topic
+        self.subscription = self.create_subscription(
+            String,
+            'joy_feedback',
+            self.listener_callback,
+            10  # QoS depth
+        )
+        self.get_logger().info('Joy Feedback Receiver Node Initialized')
+
+    def listener_callback(self, msg):
+        # Log and print the received message
+        self.get_logger().info(f'Received feedback: {msg.data}')
+
+def main(args=None):
+    rclpy.init(args=args)
+    receiver_node = JoyFeedbackReceiver()
+    try:
+        rclpy.spin(receiver_node)
+    except KeyboardInterrupt:
+        receiver_node.get_logger().info('Shutting down node...')
+    finally:
+        receiver_node.destroy_node()
+        rclpy.shutdown()
+
+if __name__ == '__main__':
+    main()
+
p9n_example/src/display_node.cpp
--- p9n_example/src/display_node.cpp
+++ p9n_example/src/display_node.cpp
@@ -14,6 +14,7 @@
 
 
 #include "p9n_example/display_node.hpp"
+#include "std_msgs/msg/string.hpp"
 
 
 namespace p9n_example
@@ -45,6 +46,10 @@
     "joy", rclcpp::SensorDataQoS(rclcpp::KeepLast(1)),
     std::bind(&DisplayNode::onJoy, this, std::placeholders::_1));
 
+  // Define the publisher
+  this->feedback_pub_ = this->create_publisher<std_msgs::msg::String>(
+    "joy_feedback", 10);
+
 
   if (this->joy_sub_->get_publisher_count() == 0) {
     RCLCPP_WARN(
@@ -57,112 +62,163 @@
 {
   this->p9n_if_->setJoyMsg(joy_msg);
 
+  std::string feedback;
+  // for handling multi button press
   if (this->p9n_if_->pressedCross()) {
+    auto msg = std_msgs::msg::String();
+    msg.data = "Cross button pressed!";
     RCLCPP_INFO(this->get_logger(), " ☓ Pressed!");
+    this->feedback_pub_->publish(msg);
   }
 
   if (this->p9n_if_->pressedCircle()) {
-    RCLCPP_INFO(this->get_logger(), " ○ Pressed!");
+      auto msg = std_msgs::msg::String();
+      msg.data = "Circle button pressed!";
+      RCLCPP_INFO(this->get_logger(), " ○ Pressed!");
+      this->feedback_pub_->publish(msg);
   }
 
   if (this->p9n_if_->pressedTriangle()) {
-    RCLCPP_INFO(this->get_logger(), " △ Pressed!");
+      auto msg = std_msgs::msg::String();
+      msg.data = "Triangle button pressed!";
+      RCLCPP_INFO(this->get_logger(), " △ Pressed!");
+      this->feedback_pub_->publish(msg);
   }
 
   if (this->p9n_if_->pressedSquare()) {
-    RCLCPP_INFO(this->get_logger(), " □ Pressed!");
+      auto msg = std_msgs::msg::String();
+      msg.data = "Square button pressed!";
+      RCLCPP_INFO(this->get_logger(), " □ Pressed!");
+      this->feedback_pub_->publish(msg);
   }
 
   if (this->p9n_if_->pressedL1()) {
-    RCLCPP_INFO(this->get_logger(), " L1 Pressed!");
+      auto msg = std_msgs::msg::String();
+      msg.data = "L1 button pressed!";
+      RCLCPP_INFO(this->get_logger(), " L1 Pressed!");
+      this->feedback_pub_->publish(msg);
   }
 
   if (this->p9n_if_->pressedR1()) {
-    RCLCPP_INFO(this->get_logger(), " R1 Pressed!");
+      auto msg = std_msgs::msg::String();
+      msg.data = "R1 button pressed!";
+      RCLCPP_INFO(this->get_logger(), " R1 Pressed!");
+      this->feedback_pub_->publish(msg);
   }
 
   if (this->p9n_if_->pressedL2()) {
-    RCLCPP_INFO_STREAM(
-      this->get_logger(),
-      " L2 Pressed! : " <<
-        std::right << std::setw(6) <<
-        std::fixed << std::setprecision(3) <<
-        this->p9n_if_->pressedL2Analog());
+      auto msg = std_msgs::msg::String();
+      msg.data = "L2 button pressed with analog value: " +
+                 std::to_string(this->p9n_if_->pressedL2Analog());
+      RCLCPP_INFO_STREAM(
+        this->get_logger(),
+        " L2 Pressed! : " << std::right << std::setw(6) << std::fixed << std::setprecision(3)
+                          << this->p9n_if_->pressedL2Analog());
+      this->feedback_pub_->publish(msg);
   }
 
   if (this->p9n_if_->pressedR2()) {
-    RCLCPP_INFO_STREAM(
-      this->get_logger(),
-      " R2 Pressed! : " <<
-        std::right << std::setw(6) <<
-        std::fixed << std::setprecision(3) <<
-        this->p9n_if_->pressedR2Analog());
+      auto msg = std_msgs::msg::String();
+      msg.data = "R2 button pressed with analog value: " +
+                 std::to_string(this->p9n_if_->pressedR2Analog());
+      RCLCPP_INFO_STREAM(
+        this->get_logger(),
+        " R2 Pressed! : " << std::right << std::setw(6) << std::fixed << std::setprecision(3)
+                          << this->p9n_if_->pressedR2Analog());
+      this->feedback_pub_->publish(msg);
   }
 
   if (this->p9n_if_->pressedSelect()) {
-    RCLCPP_INFO(
-      this->get_logger(), " Select Pressed!");
+      auto msg = std_msgs::msg::String();
+      msg.data = "Select button pressed!";
+      RCLCPP_INFO(this->get_logger(), " Select Pressed!");
+      this->feedback_pub_->publish(msg);
   }
 
   if (this->p9n_if_->pressedStart()) {
-    RCLCPP_INFO(
-      this->get_logger(), " Start Pressed!");
+      auto msg = std_msgs::msg::String();
+      msg.data = "Start button pressed!";
+      RCLCPP_INFO(this->get_logger(), " Start Pressed!");
+      this->feedback_pub_->publish(msg);
   }
 
   if (this->p9n_if_->pressedPS()) {
-    RCLCPP_INFO(
-      this->get_logger(), " PS Pressed!");
+      auto msg = std_msgs::msg::String();
+      msg.data = "PS button pressed!";
+      RCLCPP_INFO(this->get_logger(), " PS Pressed!");
+      this->feedback_pub_->publish(msg);
   }
 
   if (this->p9n_if_->pressedDPadUp()) {
-    RCLCPP_INFO(
-      this->get_logger(), " ↑ Pressed!");
+      auto msg = std_msgs::msg::String();
+      msg.data = "D-Pad Up pressed!";
+      RCLCPP_INFO(this->get_logger(), " ↑ Pressed!");
+      this->feedback_pub_->publish(msg);
   }
 
   if (this->p9n_if_->pressedDPadDown()) {
-    RCLCPP_INFO(
-      this->get_logger(), " ↓ Pressed!");
+      auto msg = std_msgs::msg::String();
+      msg.data = "D-Pad Down pressed!";
+      RCLCPP_INFO(this->get_logger(), " ↓ Pressed!");
+      this->feedback_pub_->publish(msg);
   }
 
   if (this->p9n_if_->pressedDPadRight()) {
-    RCLCPP_INFO(
-      this->get_logger(), " → Pressed!");
+      auto msg = std_msgs::msg::String();
+      msg.data = "D-Pad Right pressed!";
+      RCLCPP_INFO(this->get_logger(), " → Pressed!");
+      this->feedback_pub_->publish(msg);
   }
 
   if (this->p9n_if_->pressedDPadLeft()) {
-    RCLCPP_INFO(
-      this->get_logger(), " ← Pressed!");
+      auto msg = std_msgs::msg::String();
+      msg.data = "D-Pad Left pressed!";
+      RCLCPP_INFO(this->get_logger(), " ← Pressed!");
+      this->feedback_pub_->publish(msg);
+  }
+  
+  // L and R stick
+  if (
+      std::abs(this->p9n_if_->tiltedStickLX()) > 1e-2 ||
+      std::abs(this->p9n_if_->tiltedStickLY()) > 1e-2)
+  {
+      std::ostringstream oss;
+      oss << "LStick Tilted! x: " << std::fixed << std::setw(6) << std::setprecision(3)
+          << this->p9n_if_->tiltedStickLX()
+          << " y: " << std::fixed << std::setw(6) << std::setprecision(3)
+          << this->p9n_if_->tiltedStickLY();
+      std::string feedback = oss.str();
+
+      RCLCPP_INFO_STREAM(this->get_logger(), feedback);
+
+      // Publish the feedback message
+      auto msg = std_msgs::msg::String();
+      msg.data = feedback;
+      this->feedback_pub_->publish(msg);
   }
 
   if (
-    std::abs(this->p9n_if_->tiltedStickLX()) > 1e-2 ||
-    std::abs(this->p9n_if_->tiltedStickLY()) > 1e-2)
+      std::abs(this->p9n_if_->tiltedStickRX()) > 1e-2 ||
+      std::abs(this->p9n_if_->tiltedStickRY()) > 1e-2)
   {
-    RCLCPP_INFO_STREAM(
-      this->get_logger(),
-      " LStick Tilted!" <<
-        " x:" << std::fixed << std::setw(6) << std::setprecision(3) <<
-        this->p9n_if_->tiltedStickLX() <<
-        " y:" << std::fixed << std::setw(6) << std::setprecision(3) <<
-        this->p9n_if_->tiltedStickLY());
-  }
+      std::ostringstream oss;
+      oss << "RStick Tilted! x: " << std::fixed << std::setw(6) << std::setprecision(3)
+          << this->p9n_if_->tiltedStickRX()
+          << " y: " << std::fixed << std::setw(6) << std::setprecision(3)
+          << this->p9n_if_->tiltedStickRY();
+      std::string feedback = oss.str();
 
-  if (
-    std::abs(this->p9n_if_->tiltedStickRX()) > 1e-2 ||
-    std::abs(this->p9n_if_->tiltedStickRY()) > 1e-2)
-  {
-    RCLCPP_INFO_STREAM(
-      this->get_logger(),
-      " RStick Tilted!" <<
-        " x:" << std::fixed << std::setw(6) << std::setprecision(3) <<
-        this->p9n_if_->tiltedStickRX() <<
-        " y:" << std::fixed << std::setw(6) << std::setprecision(3) <<
-        this->p9n_if_->tiltedStickRY());
+      RCLCPP_INFO_STREAM(this->get_logger(), feedback);
+
+      // Publish the feedback message
+      auto msg = std_msgs::msg::String();
+      msg.data = feedback;
+      this->feedback_pub_->publish(msg);
   }
 
   if (this->p9n_if_->pressedAny()) {
     using namespace std::chrono_literals;  // NOLINT
-    rclcpp::sleep_for(200ms);
+    rclcpp::sleep_for(100ms);
   }
 }
 }  // namespace p9n_example
Add a comment
List