mirror of
https://github.com/6-robot/wpr_simulation2.git
synced 2025-09-15 12:58:54 +08:00
add demo_3_class
This commit is contained in:
parent
77ec540ea1
commit
d1771c94e8
36
demo_cpp/3_publisher_class.cpp
Normal file
36
demo_cpp/3_publisher_class.cpp
Normal file
@ -0,0 +1,36 @@
|
||||
#include "rclcpp/rclcpp.hpp"
|
||||
#include "std_msgs/msg/string.hpp"
|
||||
|
||||
class PublisherNode : public rclcpp::Node
|
||||
{
|
||||
public:
|
||||
PublisherNode()
|
||||
: Node("publisher_node")
|
||||
{
|
||||
publisher_ = create_publisher<std_msgs::msg::String>("/my_topic", 10);
|
||||
timer_ = create_wall_timer(
|
||||
std::chrono::milliseconds(1000),
|
||||
std::bind(&PublisherNode::publishMessage, this)
|
||||
);
|
||||
}
|
||||
|
||||
private:
|
||||
void publishMessage()
|
||||
{
|
||||
message_.data = "Hello World!";
|
||||
publisher_->publish(message_);
|
||||
}
|
||||
|
||||
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher_;
|
||||
std_msgs::msg::String message_;
|
||||
rclcpp::TimerBase::SharedPtr timer_;
|
||||
};
|
||||
|
||||
int main(int argc, char * argv[])
|
||||
{
|
||||
rclcpp::init(argc, argv);
|
||||
auto node = std::make_shared<PublisherNode>();
|
||||
rclcpp::spin(node);
|
||||
rclcpp::shutdown();
|
||||
return 0;
|
||||
}
|
||||
32
demo_cpp/3_subscriber_class.cpp
Normal file
32
demo_cpp/3_subscriber_class.cpp
Normal file
@ -0,0 +1,32 @@
|
||||
#include "rclcpp/rclcpp.hpp"
|
||||
#include "std_msgs/msg/string.hpp"
|
||||
|
||||
class SubscriberNode : public rclcpp::Node
|
||||
{
|
||||
public:
|
||||
SubscriberNode()
|
||||
: Node("subscriber_node")
|
||||
{
|
||||
subscriber_ = create_subscription<std_msgs::msg::String>(
|
||||
"/my_topic",
|
||||
10,
|
||||
std::bind(&SubscriberNode::callback, this, std::placeholders::_1));
|
||||
}
|
||||
|
||||
private:
|
||||
void callback(const std_msgs::msg::String::SharedPtr msg)
|
||||
{
|
||||
RCLCPP_INFO(get_logger(), "Receive : %s", msg->data.c_str());
|
||||
}
|
||||
|
||||
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subscriber_;
|
||||
};
|
||||
|
||||
int main(int argc, char * argv[])
|
||||
{
|
||||
rclcpp::init(argc, argv);
|
||||
auto node = std::make_shared<SubscriberNode>();
|
||||
rclcpp::spin(node);
|
||||
rclcpp::shutdown();
|
||||
return 0;
|
||||
}
|
||||
Loading…
Reference in New Issue
Block a user