src/Comms/common.cpp
Go to the documentation of this file.
1 /*+-------------------------------------------------------------------------+
2  | MultiVehicle simulator (libmvsim) |
3  | |
4  | Copyright (C) 2014-2024 Jose Luis Blanco Claraco |
5  | Copyright (C) 2017 Borys Tymchenko (Odessa Polytechnic University) |
6  | Distributed under 3-clause BSD License |
7  | See COPYING |
8  +-------------------------------------------------------------------------+ */
9 
10 #include <mrpt/core/exceptions.h>
11 
12 #if defined(MVSIM_HAS_ZMQ) && defined(MVSIM_HAS_PROTOBUF)
13 #include <google/protobuf/message.h>
14 #include <mvsim/Comms/common.h>
15 
16 #include <zmq.hpp>
17 
18 using namespace mvsim;
19 
20 void mvsim::sendMessage(const google::protobuf::MessageLite& m, zmq::socket_t& socket)
21 {
22  mrpt::io::CMemoryStream buf;
23  auto arch = mrpt::serialization::archiveFrom(buf);
24 
25  arch << m.GetTypeName();
26  arch << m.SerializeAsString();
27 
28  zmq::message_t msg(buf.getRawBufferData(), buf.getTotalBytesCount());
29 #if CPPZMQ_VERSION >= ZMQ_MAKE_VERSION(4, 3, 1)
30  socket.send(msg, zmq::send_flags::none);
31 #else
32  socket.send(msg);
33 #endif
34 }
35 
36 std::tuple<std::string, std::string> mvsim::internal::parseMessageToParts(const zmq::message_t& msg)
37 {
38  mrpt::io::CMemoryStream buf;
39  buf.assignMemoryNotOwn(msg.data(), msg.size());
40 
41  auto arch = mrpt::serialization::archiveFrom(buf);
42 
43  std::string typeName, serializedData;
44  arch >> typeName >> serializedData;
45  return {typeName, serializedData};
46 }
47 
48 void mvsim::parseMessage(const zmq::message_t& msg, google::protobuf::MessageLite& out)
49 {
50  const auto [typeName, serializedData] = internal::parseMessageToParts(msg);
51 
52  ASSERT_EQUAL_(typeName, out.GetTypeName());
53 
54  bool ok = out.ParseFromString(serializedData);
55  if (!ok)
56  THROW_EXCEPTION_FMT(
57  "Format error: protobuf could not decode binary message of "
58  "type "
59  "'%s'",
60  typeName.c_str());
61 }
62 
63 zmq::message_t mvsim::receiveMessage(zmq::socket_t& s)
64 {
65  zmq::message_t m;
66 #if CPPZMQ_VERSION >= ZMQ_MAKE_VERSION(4, 3, 1)
67  std::optional<size_t> msgSize = s.recv(m);
68  ASSERT_(msgSize.has_value());
69 #else
70  s.recv(&m);
71 #endif
72  return m;
73 }
74 
75 std::string mvsim::get_zmq_endpoint(const zmq::socket_t& s)
76 {
77 #if CPPZMQ_VERSION > ZMQ_MAKE_VERSION(4, 7, 0)
78  return s.get(zmq::sockopt::last_endpoint);
79 #else
80  char assignedPort[200];
81  size_t assignedPortLen = sizeof(assignedPort);
82  s.getsockopt(ZMQ_LAST_ENDPOINT, &assignedPort, &assignedPortLen);
83  assignedPort[assignedPortLen] = '\0';
84  return {assignedPort};
85 #endif
86 }
87 
88 #endif
mvsim
Definition: Client.h:21
s
XmlRpcServer s
ok
ROSCPP_DECL bool ok()
common.h


mvsim
Author(s):
autogenerated on Wed May 28 2025 02:13:07