Compare commits

...

2 Commits

Author SHA1 Message Date
Jérôme BEDIER 1b2d482dd2 Merge branch 'develop' 2025-11-18 14:52:30 +01:00
Jérôme BEDIER 21ef1667c4 trying to make it move ? 2025-11-18 14:25:20 +01:00
1 changed files with 23 additions and 6 deletions

View File

@ -5,32 +5,49 @@
class CmdPublisher : public rclcpp::Node class CmdPublisher : public rclcpp::Node
{ {
public: 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<geometry_msgs::msg::Twist>("/cmd_vel", 10); publisher_ = this->create_publisher<geometry_msgs::msg::Twist>("/cmd_vel", 10);
// Publish at 10 Hz for continuous movement
timer_ = this->create_wall_timer( timer_ = this->create_wall_timer(
std::chrono::seconds(1), std::chrono::milliseconds(100),
std::bind(&CmdPublisher::timer_callback, this)); 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: 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() void timer_callback()
{ {
auto message = geometry_msgs::msg::Twist(); 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); publisher_->publish(message);
} }
rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr publisher_; rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr publisher_;
rclcpp::TimerBase::SharedPtr timer_; rclcpp::TimerBase::SharedPtr timer_;
rclcpp::TimerBase::SharedPtr random_timer_;
std::random_device rd_; std::random_device rd_;
std::mt19937 gen_; std::mt19937 gen_;
std::uniform_real_distribution<> dis_; std::uniform_real_distribution<> dis_;
double current_angular_z_;
}; };
int main(int argc, char * argv[]) int main(int argc, char * argv[])