python/generated-sources-pybind/mvsim/Comms/Client.cpp
Go to the documentation of this file.
1 #include <mrpt/system/CTimeLogger.h>
2 #include <mvsim/Comms/Client.h>
3 #include <pybind11/functional.h>
4 #include <pybind11/pybind11.h>
5 #include <pybind11/stl.h>
6 
7 #include <functional>
8 #include <iterator>
9 #include <memory>
10 #include <sstream> // __str__
11 #include <string>
12 #include <string_view>
13 
14 #ifndef BINDER_PYBIND11_TYPE_CASTER
15 #define BINDER_PYBIND11_TYPE_CASTER
16 PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr<T>)
17 PYBIND11_DECLARE_HOLDER_TYPE(T, T*)
18 PYBIND11_MAKE_OPAQUE(std::shared_ptr<void>)
19 #endif
20 
22  std::function<pybind11::module&(std::string const& namespace_)>& M)
23 {
24  { // mvsim::Client file:mvsim/Comms/Client.h line:48
25  pybind11::class_<mvsim::Client, std::shared_ptr<mvsim::Client>> cl(
26  M("mvsim"), "Client",
27  "This is the connection of any user program with the MVSIM server, "
28  "so\n it can advertise and subscribe to topics and use remote "
29  "services.\n\n Users should instance a class mvsim::Client (C++) "
30  "or mvsim.Client (Python) to\n communicate with the simulation "
31  "runnin in mvsim::World or any other module.\n\n Usage:\n - "
32  "Instantiate a Client object.\n - Call connect(). It will return "
33  "immediately.\n - The client will be working on the background as "
34  "long as the object is not\n destroyed.\n\n Messages and topics "
35  "are described as Protobuf messages, and communications\n are done "
36  "via ZMQ sockets.\n\n See: https://mvsimulator.readthedocs.io/\n\n "
37  "\n\n ");
38  cl.def(pybind11::init([]() { return new mvsim::Client(); }));
39  cl.def(pybind11::init<const std::string&>(), pybind11::arg("nodeName"));
40 
41  cl.def(
42  "setName",
43  (void (mvsim::Client::*)(const std::string&)) &
45  "@{ \n\nC++: mvsim::Client::setName(const std::string &) --> void",
46  pybind11::arg("nodeName"));
47  cl.def(
48  "serverHostAddress",
49  (const std::string& (mvsim::Client::*)() const) &
51  "C++: mvsim::Client::serverHostAddress() const --> const "
52  "std::string &",
53  pybind11::return_value_policy::automatic);
54  cl.def(
55  "serverHostAddress",
56  (void (mvsim::Client::*)(const std::string&)) &
58  "C++: mvsim::Client::serverHostAddress(const std::string &) --> "
59  "void",
60  pybind11::arg("serverIpOrAddressName"));
61  cl.def(
62  "connect", (void (mvsim::Client::*)()) & mvsim::Client::connect,
63  "Connects to the server in a parallel thread.\n Default server "
64  "address is `localhost`, can be changed with\n "
65  "serverHostAddress().\n\nC++: mvsim::Client::connect() --> void");
66  cl.def(
67  "connected",
68  (bool (mvsim::Client::*)() const) & mvsim::Client::connected,
69  "Whether the client is correctly connected to the server. \n\nC++: "
70  "mvsim::Client::connected() const --> bool");
71  cl.def(
72  "shutdown", (void (mvsim::Client::*)()) & mvsim::Client::shutdown,
73  "Shutdowns the communication thread. Blocks until the thread is "
74  "stopped.\n There is no need to manually call this method, it is "
75  "called upon\n destruction. \n\nC++: mvsim::Client::shutdown() --> "
76  "void");
77  cl.def(
78  "callService",
79  (std::string(mvsim::Client::*)(
80  const std::string&, const std::string&)) &
82  "Overload for python wrapper\n\nC++: "
83  "mvsim::Client::callService(const std::string &, const std::string "
84  "&) --> std::string",
85  pybind11::arg("serviceName"), pybind11::arg("inputSerializedMsg"));
86  cl.def(
87  "subscribeTopic",
88  (void (mvsim::Client::*)(
89  const std::string&,
90  const class std::function<void(
91  const std::string&,
92  const class std::vector<
93  unsigned char,
94  class std::allocator<unsigned char>>&)>&)) &
96  "Overload for python wrapper (callback accepts "
97  "bytes-string)\n\nC++: mvsim::Client::subscribeTopic(const "
98  "std::string &, const class std::function<void (const std::string "
99  "&, const class std::vector<unsigned char, class "
100  "std::allocator<unsigned char> > &)> &) --> void",
101  pybind11::arg("topicName"), pybind11::arg("callback"));
102  cl.def(
103  "enable_profiler",
104  (void (mvsim::Client::*)(bool)) & mvsim::Client::enable_profiler,
105  "C++: mvsim::Client::enable_profiler(bool) --> void",
106  pybind11::arg("enable"));
107 
108  { // mvsim::Client::InfoPerNode file:mvsim/Comms/Client.h line:113
109  auto& enclosing_class = cl;
110  pybind11::class_<
112  std::shared_ptr<mvsim::Client::InfoPerNode>>
113  cl(enclosing_class, "InfoPerNode", "");
114  cl.def(pybind11::init(
115  []() { return new mvsim::Client::InfoPerNode(); }));
116  cl.def(pybind11::init([](mvsim::Client::InfoPerNode const& o) {
117  return new mvsim::Client::InfoPerNode(o);
118  }));
119  cl.def_readwrite("name", &mvsim::Client::InfoPerNode::name);
120  cl.def(
121  "assign",
122  (struct mvsim::Client::InfoPerNode &
123  (mvsim::Client::InfoPerNode::*)(const struct mvsim::Client::
124  InfoPerNode&)) &
125  mvsim::Client::InfoPerNode::operator=,
126  "C++: mvsim::Client::InfoPerNode::operator=(const struct "
127  "mvsim::Client::InfoPerNode &) --> struct "
128  "mvsim::Client::InfoPerNode &",
129  pybind11::return_value_policy::automatic, pybind11::arg(""));
130  }
131 
132  { // mvsim::Client::InfoPerTopic file:mvsim/Comms/Client.h line:119
133  auto& enclosing_class = cl;
134  pybind11::class_<
136  std::shared_ptr<mvsim::Client::InfoPerTopic>>
137  cl(enclosing_class, "InfoPerTopic", "");
138  cl.def(pybind11::init(
139  []() { return new mvsim::Client::InfoPerTopic(); }));
140  cl.def(pybind11::init([](mvsim::Client::InfoPerTopic const& o) {
141  return new mvsim::Client::InfoPerTopic(o);
142  }));
143  cl.def_readwrite("name", &mvsim::Client::InfoPerTopic::name);
144  cl.def_readwrite("type", &mvsim::Client::InfoPerTopic::type);
145  cl.def_readwrite(
147  cl.def_readwrite(
149  cl.def(
150  "assign",
151  (struct mvsim::Client::InfoPerTopic &
152  (mvsim::Client::InfoPerTopic::*)(const struct mvsim::Client::
153  InfoPerTopic&)) &
154  mvsim::Client::InfoPerTopic::operator=,
155  "C++: mvsim::Client::InfoPerTopic::operator=(const struct "
156  "mvsim::Client::InfoPerTopic &) --> struct "
157  "mvsim::Client::InfoPerTopic &",
158  pybind11::return_value_policy::automatic, pybind11::arg(""));
159  }
160  }
161 }
std::vector< std::string > endpoints
Definition: Client.h:123
void enable_profiler(bool enable)
Definition: Client.h:135
void shutdown() noexcept
void setName(const std::string &nodeName)
void subscribeTopic(const std::string &topicName, const std::function< void(const MSG_T &)> &callback)
Definition: Client.h:207
void bind_mvsim_Comms_Client(std::function< pybind11::module &(std::string const &namespace_)> &M)
void callService(const std::string &serviceName, const INPUT_MSG_T &input, OUTPUT_MSG_T &output)
Definition: Client.h:221
bool connected() const
const std::string & serverHostAddress() const
Definition: Client.h:60
std::vector< std::string > publishers
Definition: Client.h:123


mvsim
Author(s):
autogenerated on Tue Jul 4 2023 03:08:19