From 21ef1667c44b4a35e362101dd0cbe1017c530e17 Mon Sep 17 00:00:00 2001 From: "jerome.bedier" Date: Tue, 18 Nov 2025 14:25:20 +0100 Subject: [PATCH] trying to make it move ? --- ros_midterm/src/cmd_pub.cpp | 29 +++++++++++++++++++++++------ 1 file changed, 23 insertions(+), 6 deletions(-) diff --git a/ros_midterm/src/cmd_pub.cpp b/ros_midterm/src/cmd_pub.cpp index 00b180f..c0783d0 100644 --- a/ros_midterm/src/cmd_pub.cpp +++ b/ros_midterm/src/cmd_pub.cpp @@ -5,32 +5,49 @@ class CmdPublisher : public rclcpp::Node { public: - CmdPublisher() : Node("cmd_pub"), gen_(rd_()), dis_(-2.0, 2.0) + CmdPublisher() : Node("cmd_pub"), gen_(rd_()), dis_(-1.0, 1.0) { publisher_ = this->create_publisher("/cmd_vel", 10); + + // Publish at 10 Hz for continuous movement timer_ = this->create_wall_timer( - std::chrono::seconds(1), + std::chrono::milliseconds(100), std::bind(&CmdPublisher::timer_callback, this)); - RCLCPP_INFO(this->get_logger(), "CMD Publisher node started"); + // Generate new random angular velocity every second + random_timer_ = this->create_wall_timer( + std::chrono::seconds(1), + std::bind(&CmdPublisher::generate_random_velocity, this)); + + current_angular_z_ = dis_(gen_); + RCLCPP_INFO(this->get_logger(), "CMD Publisher node started - Publishing at 10Hz"); } private: + void generate_random_velocity() + { + current_angular_z_ = dis_(gen_); + RCLCPP_INFO(this->get_logger(), "New Random Angular Velocity Z: %.4f rad/s", + current_angular_z_); + } + void timer_callback() { auto message = geometry_msgs::msg::Twist(); - message.angular.z = dis_(gen_); + // Add small linear velocity to help TurtleBot3 move + message.linear.x = 0.1; // Small forward movement + message.angular.z = current_angular_z_; - RCLCPP_INFO(this->get_logger(), "Publishing Angular Velocity Z: %.4f rad/s", - message.angular.z); publisher_->publish(message); } rclcpp::Publisher::SharedPtr publisher_; rclcpp::TimerBase::SharedPtr timer_; + rclcpp::TimerBase::SharedPtr random_timer_; std::random_device rd_; std::mt19937 gen_; std::uniform_real_distribution<> dis_; + double current_angular_z_; }; int main(int argc, char * argv[])