From 9aa510c1f7429457a0819a3e28b75781fcba6dde Mon Sep 17 00:00:00 2001 From: joey Date: Fri, 23 Aug 2024 18:31:48 +0800 Subject: [PATCH] finalise --- mini_pupper_interfaces/CMakeLists.txt | 1 + .../mini_pupper_recognition/pid_line_following_node.py | 3 ++- 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/mini_pupper_interfaces/CMakeLists.txt b/mini_pupper_interfaces/CMakeLists.txt index 53e680c..a2a8a6c 100644 --- a/mini_pupper_interfaces/CMakeLists.txt +++ b/mini_pupper_interfaces/CMakeLists.txt @@ -18,6 +18,7 @@ rosidl_generate_interfaces(${PROJECT_NAME} "srv/PlayMusic.srv" "srv/StopMusic.srv" "msg/LineDetectionResult.msg" + "msg/AiLineRecognitionResult.msg" DEPENDENCIES std_msgs # Add packages that above messages depend on, in this case geometry_msgs for Sphere.msg ) diff --git a/mini_pupper_recognition/mini_pupper_recognition/pid_line_following_node.py b/mini_pupper_recognition/mini_pupper_recognition/pid_line_following_node.py index f9c06cc..22d1163 100644 --- a/mini_pupper_recognition/mini_pupper_recognition/pid_line_following_node.py +++ b/mini_pupper_recognition/mini_pupper_recognition/pid_line_following_node.py @@ -18,6 +18,7 @@ import rclpy from rclpy.node import Node +from std_msgs.msg import String from geometry_msgs.msg import Twist import time from simple_pid import PID @@ -49,7 +50,7 @@ def _vel_callback(self, msg): velocity_cmd = Twist() if msg.linear != '': - self.linear_vel = float(msg.linear) * 2 # Scale the linear velocity + self.linear_vel = float(msg.linear) / 5 # Scale the linear velocity self.angular_vel = float(msg.angular) / 3 # Scale the angular velocity control_linear = self.pid_linear(self.linear_vel)