#include<iostream>#include<thread>#include"zenoh.hxx"usingnamespacezenoh;voidtask1(){Configconfig=Config::create_default();autosession=Session::open(std::move(config));// auto publisher = session.declare_publisher(KeyExpr("demo/example/simple"));for(inti=0;i<5;++i){// Publish using session.putsession.put(KeyExpr("demo/example/simple"),Bytes("Simple from session.put! i="+std::to_string(i)));// Publish using publisher.put// publisher.put("Simple from publisher.put!");std::this_thread::sleep_for(std::chrono::seconds(1));}}intmain(){std::threadt1(task1);Configconfig=Config::create_default();autosession=Session::open(std::move(config));autosubscriber=session.declare_subscriber(KeyExpr("demo/example/simple"),[](constSample&sample){std::cout<<"Received: "<<sample.get_payload().as_string()<<std::endl;},closures::none);t1.join();// Wait for task1 to finishstd::cout<<"Demo completed.\n";return0;}
#include<iostream>#include<thread>#include"zenoh.hxx"#include<rclcpp/rclcpp.hpp>#include<std_msgs/msg/int32.hpp>#include<rclcpp/serialization.hpp>#include<rclcpp/serialized_message.hpp>usingnamespacezenoh;std::vector<uint8_t>serialize_ros_message(conststd_msgs::msg::Int32&msg){rclcpp::Serialization<std_msgs::msg::Int32>serializer;rclcpp::SerializedMessageserialized_msg;serializer.serialize_message(&msg,&serialized_msg);// Copy message block of memory to std::vectorstd::vector<uint8_t>buffer(serialized_msg.get_rcl_serialized_message().buffer,serialized_msg.get_rcl_serialized_message().buffer+serialized_msg.get_rcl_serialized_message().buffer_length);returnbuffer;}std_msgs::msg::Int32deserialize_ros_message(conststd::vector<uint8_t>&buffer){rclcpp::SerializedMessageserialized_msg;// Resize internal buffer and copyserialized_msg.get_rcl_serialized_message().buffer_capacity=buffer.size();serialized_msg.get_rcl_serialized_message().buffer_length=buffer.size();serialized_msg.get_rcl_serialized_message().buffer=reinterpret_cast<uint8_t*>(malloc(buffer.size()));std::memcpy(serialized_msg.get_rcl_serialized_message().buffer,buffer.data(),buffer.size());rclcpp::Serialization<std_msgs::msg::Int32>serializer;std_msgs::msg::Int32msg;serializer.deserialize_message(&serialized_msg,&msg);returnmsg;}voidtask1(){Configconfig=Config::create_default();autosession=Session::open(std::move(config));// auto publisher = session.declare_publisher(KeyExpr("demo/example/simple"));for(inti=0;i<5;++i){std_msgs::msg::Int32msg;msg.data=i;autobuffer=serialize_ros_message(msg);// Publish using session.putsession.put(KeyExpr("demo/example/simple"),buffer);// Publish using publisher.put// publisher.put("Simple from publisher.put!");std::this_thread::sleep_for(std::chrono::seconds(1));}}intmain(){std::threadt1(task1);Configconfig=Config::create_default();autosession=Session::open(std::move(config));autosubscriber=session.declare_subscriber(KeyExpr("demo/example/simple"),[](constSample&sample){autobuffer=sample.get_payload().as_vector();automsg=deserialize_ros_message(buffer);std::cout<<"Received: "<<msg.data<<std::endl;},closures::none);t1.join();// Wait for task1 to finishstd::cout<<"Both tasks completed.\n";return0;}
#include<iostream>#include<thread>#include"zenoh.hxx"#include<rclcpp/rclcpp.hpp>#include<std_msgs/msg/int32.hpp>#include<rclcpp/serialization.hpp>#include<rclcpp/serialized_message.hpp>// sudo apt install libfastcdr-devusingnamespacezenoh;std_msgs::msg::Int32deserialize_ros_message(conststd::vector<uint8_t>&buffer){rclcpp::SerializedMessageserialized_msg;// Resize internal buffer and copyserialized_msg.get_rcl_serialized_message().buffer_capacity=buffer.size();serialized_msg.get_rcl_serialized_message().buffer_length=buffer.size();serialized_msg.get_rcl_serialized_message().buffer=reinterpret_cast<uint8_t*>(malloc(buffer.size()));std::memcpy(serialized_msg.get_rcl_serialized_message().buffer,buffer.data(),buffer.size());rclcpp::Serialization<std_msgs::msg::Int32>serializer;std_msgs::msg::Int32msg;serializer.deserialize_message(&serialized_msg,&msg);returnmsg;}intmain(intargc,char**argv){Configconfig=Config::create_default();autosession=Session::open(std::move(config));autosubscriber=session.declare_subscriber(KeyExpr("my_int32_topic"),[](constSample&sample){autobuffer=sample.get_payload().as_vector();automsg=deserialize_ros_message(buffer);std::cout<<"Received: "<<msg.data<<std::endl;},closures::none);// Wait for a key press to exitcharc=getchar();}