added the cmd_pub.cpp
This commit is contained in:
parent
ab2cd23aa6
commit
70e8b5326d
|
|
@ -0,0 +1,42 @@
|
||||||
|
#include "rclcpp/rclcpp.hpp"
|
||||||
|
#include "geometry_msgs/msg/twist.hpp"
|
||||||
|
#include <random>
|
||||||
|
|
||||||
|
class CmdPublisher : public rclcpp::Node
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
CmdPublisher() : Node("cmd_pub"), gen_(rd_()), dis_(-2.0, 2.0)
|
||||||
|
{
|
||||||
|
publisher_ = this->create_publisher<geometry_msgs::msg::Twist>("/cmd_vel", 10);
|
||||||
|
timer_ = this->create_wall_timer(
|
||||||
|
std::chrono::seconds(1),
|
||||||
|
std::bind(&CmdPublisher::timer_callback, this));
|
||||||
|
|
||||||
|
RCLCPP_INFO(this->get_logger(), "CMD Publisher node started");
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
void timer_callback()
|
||||||
|
{
|
||||||
|
auto message = geometry_msgs::msg::Twist();
|
||||||
|
message.angular.z = dis_(gen_);
|
||||||
|
|
||||||
|
RCLCPP_INFO(this->get_logger(), "Publishing Angular Velocity Z: %.4f rad/s",
|
||||||
|
message.angular.z);
|
||||||
|
publisher_->publish(message);
|
||||||
|
}
|
||||||
|
|
||||||
|
rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr publisher_;
|
||||||
|
rclcpp::TimerBase::SharedPtr timer_;
|
||||||
|
std::random_device rd_;
|
||||||
|
std::mt19937 gen_;
|
||||||
|
std::uniform_real_distribution<> dis_;
|
||||||
|
};
|
||||||
|
|
||||||
|
int main(int argc, char * argv[])
|
||||||
|
{
|
||||||
|
rclcpp::init(argc, argv);
|
||||||
|
rclcpp::spin(std::make_shared<CmdPublisher>());
|
||||||
|
rclcpp::shutdown();
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
Loading…
Reference in New Issue