Skip to content
Snippets Groups Projects
Commit 62c53252 authored by Johannes Mey's avatar Johannes Mey
Browse files

send data using protobuf

parent d60fe2c5
No related branches found
No related tags found
No related merge requests found
......@@ -12,6 +12,11 @@ find_package(catkin REQUIRED roscpp)
## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system)
find_package(Protobuf 3 REQUIRED)
include_directories(${Protobuf_INCLUDE_DIRS})
include_directories(${CMAKE_CURRENT_BINARY_DIR})
protobuf_generate_cpp(PROTO_SRCS PROTO_HDRS proto/Ping.proto)
# make sure NNG is updated in the submodule
execute_process(COMMAND git submodule update --init -- lib/nng
WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR})
......@@ -104,7 +109,7 @@ add_subdirectory(lib/nng)
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
# INCLUDE_DIRS include
LIBRARIES nng_test
# LIBRARIES nng_test
# CATKIN_DEPENDS other_catkin_pkg
# DEPENDS system_lib
)
......@@ -133,8 +138,8 @@ include_directories(
## Declare a C++ executable
## With catkin_make all packages are built within a single CMake context
## The recommended prefix ensures that target names across packages don't collide
add_executable(${PROJECT_NAME}_sender src/nng_sender.cpp)
add_executable(${PROJECT_NAME}_receiver src/nng_receiver.cpp)
add_executable(${PROJECT_NAME}_sender src/nng_sender.cpp ${PROTO_SRCS} ${PROTO_HDRS})
add_executable(${PROJECT_NAME}_receiver src/nng_receiver.cpp ${PROTO_SRCS} ${PROTO_HDRS})
## Rename C++ executable without prefix
## The above recommended prefix causes long target names, the following renames the
......@@ -151,10 +156,12 @@ set_target_properties(${PROJECT_NAME}_receiver PROPERTIES OUTPUT_NAME receiver P
target_link_libraries(${PROJECT_NAME}_sender
${catkin_LIBRARIES}
nng
${Protobuf_LIBRARIES}
)
target_link_libraries(${PROJECT_NAME}_receiver
${catkin_LIBRARIES}
nng
${Protobuf_LIBRARIES}
)
#############
......
<?xml version="1.0"?>
<package format="2">
<name>nng_test</name>
<version>0.0.0</version>
<version>0.1.0</version>
<description>a sender and receiver node using nng</description>
<!-- One maintainer tag required, multiple allowed, one person per tag -->
......@@ -30,7 +30,8 @@
<!-- Dependencies can be catkin packages or system dependencies -->
<!-- Examples: -->
<!-- Use depend as a shortcut for packages that are both build and exec dependencies -->
<!-- <depend>roscpp</depend> -->
<depend>roscpp</depend>
<build_depend>protobuf-dev</build_depend>
<!-- Note that this is equivalent to the following: -->
<!-- <build_depend>roscpp</build_depend> -->
<!-- <exec_depend>roscpp</exec_depend> -->
......
syntax = "proto3";
message Ping {
string name = 1;
}
\ No newline at end of file
......@@ -10,7 +10,9 @@
#include <nng/protocol/pubsub0/sub.h>
#include <std_msgs/String.h>
std::string url = "tcp://localhost:6576";
#include "Ping.pb.h"
const std::string URL = "tcp://localhost:6576";
int main(int argc, char **argv) {
ros::init(argc, argv, "nng_receiver");
......@@ -32,7 +34,7 @@ int main(int argc, char **argv) {
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) {
if ((rv = nng_dial(sock, URL.c_str(), nullptr, 0)) != 0) {
ROS_ERROR_STREAM("nng_dial returned: " << nng_strerror(rv));
}
......@@ -42,15 +44,16 @@ int main(int argc, char **argv) {
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);
// store the result in a protobuf object and free the buffer
Ping ping;
ping.ParseFromArray(buf, sz);
nng_free(buf, sz);
ROS_INFO_STREAM("CLIENT: RECEIVED '" << result << "'");
ROS_INFO_STREAM("CLIENT: RECEIVED '" << ping.name() << "'");
// build and publish a ROS message
std_msgs::String msg;
msg.data = result;
msg.data = ping.name();
ROS_INFO_STREAM("Publishing ROS message '" << msg.data << "'");
nng_receiver_pub.publish(msg);
} else if (rv == NNG_EAGAIN) {
......@@ -64,6 +67,5 @@ int main(int argc, char **argv) {
loop_rate.sleep();
}
return 0;
}
\ No newline at end of file
......@@ -8,19 +8,32 @@
#include <nng/nng.h>
#include <nng/protocol/pubsub0/pub.h>
std::string url = "tcp://localhost:6576";
#include "Ping.pb.h"
const std::string URL = "tcp://localhost:6576";
nng_socket sock;
int rv;
void nngCallback(const std_msgs::String::ConstPtr &msg) {
ROS_INFO("sending via NNG: [%s]", msg->data.c_str());
if ((rv = nng_send(sock, (void *) msg->data.c_str(), msg->data.length(), 0)) != 0) {
// wrap into protobuf message
Ping ping;
ping.set_name(msg->data);
int length = ping.ByteSize();
void *data = nng_alloc(length);
ping.SerializeToArray(data, length);
if ((rv = nng_send(sock, data, length, NNG_FLAG_ALLOC)) != 0) {
ROS_ERROR_STREAM("nng_send returned: " << nng_strerror(rv));
}
}
int main(int argc, char **argv) {
GOOGLE_PROTOBUF_VERIFY_VERSION;
ros::init(argc, argv, "nng_sender");
ros::NodeHandle n("nnc_test");
......@@ -28,7 +41,7 @@ int main(int argc, char **argv) {
if ((rv = nng_pub0_open(&sock)) != 0) {
ROS_ERROR_STREAM("nng_pub0_open returned: " << nng_strerror(rv));
}
if ((rv = nng_listen(sock, url.c_str(), nullptr, 0)) < 0) {
if ((rv = nng_listen(sock, URL.c_str(), nullptr, 0)) < 0) {
ROS_ERROR_STREAM("nng_listen returned: " << nng_strerror(rv));
}
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment