Select Git revision
nng_receiver.cpp
nng_receiver.cpp 1.64 KiB
//
// Created by Johannes Mey on 26.05.20.
//
#include "ros/ros.h"
#include <sstream>
#include <nng/nng.h>
#include <nng/protocol/pubsub0/sub.h>
#include <std_msgs/String.h>
std::string url = "tcp://localhost:6576";
int main(int argc, char **argv) {
ros::init(argc, argv, "nng_receiver");
ros::NodeHandle n("nnc_test");
ros::Publisher nng_receiver_pub = n.advertise<std_msgs::String>("received_nng", 1000);
ros::Rate loop_rate(200);
nng_socket sock;
int rv;
if ((rv = nng_sub0_open(&sock)) != 0) {
ROS_ERROR_STREAM("nng_sub0_open returned: " << nng_strerror(rv));
}
// subscribe to everything (empty means all topics)
if ((rv = nng_setopt(sock, NNG_OPT_SUB_SUBSCRIBE, "", 0)) != 0) {
ROS_ERROR_STREAM("nng_setopt returned: " << nng_strerror(rv));
}
if ((rv = nng_dial(sock, url.c_str(), nullptr, 0)) != 0) {
ROS_ERROR_STREAM("nng_dial returned: " << nng_strerror(rv));
}
while (ros::ok()) {
char *buf = nullptr;
size_t sz;
if ((rv = nng_recv(sock, &buf, &sz, NNG_FLAG_ALLOC | NNG_FLAG_NONBLOCK)) == 0) {
// store the result in a string and free the buffer
std::string result(buf, sz);
nng_free(buf, sz);
ROS_INFO_STREAM("CLIENT: RECEIVED '" << result << "'");
// build and publish a ROS message
std_msgs::String msg;
msg.data = result;
ROS_INFO_STREAM("Publishing ROS message '" << msg.data << "'");
nng_receiver_pub.publish(msg);
} else if (rv == NNG_EAGAIN) {
// no message received in current spin
} else {
ROS_ERROR_STREAM("nng_recv returned: " << nng_strerror(rv));
}
ros::spinOnce();
loop_rate.sleep();
}
return 0;
}