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 
21 void bind_mvsim_Comms_Client(std::function<pybind11::module&(std::string const& namespace_)>& M)
22 {
23  { // mvsim::Client file:mvsim/Comms/Client.h line:48
24  pybind11::class_<mvsim::Client, std::shared_ptr<mvsim::Client>> cl(
25  M("mvsim"), "Client",
26  "This is the connection of any user program with the MVSIM server, "
27  "so\n it can advertise and subscribe to topics and use remote "
28  "services.\n\n Users should instance a class mvsim::Client (C++) "
29  "or mvsim.Client (Python) to\n communicate with the simulation "
30  "runnin in mvsim::World or any other module.\n\n Usage:\n - "
31  "Instantiate a Client object.\n - Call connect(). It will return "
32  "immediately.\n - The client will be working on the background as "
33  "long as the object is not\n destroyed.\n\n Messages and topics "
34  "are described as Protobuf messages, and communications\n are done "
35  "via ZMQ sockets.\n\n See: https://mvsimulator.readthedocs.io/\n\n "
36  "\n\n ");
37  cl.def(pybind11::init([]() { return new mvsim::Client(); }));
38  cl.def(pybind11::init<const std::string&>(), pybind11::arg("nodeName"));
39 
40  cl.def(
41  "setName", (void(mvsim::Client::*)(const std::string&)) & mvsim::Client::setName,
42  "@{ \n\nC++: mvsim::Client::setName(const std::string &) --> void",
43  pybind11::arg("nodeName"));
44  cl.def(
45  "serverHostAddress",
46  (const std::string& (mvsim::Client::*)() const) & mvsim::Client::serverHostAddress,
47  "C++: mvsim::Client::serverHostAddress() const --> const "
48  "std::string &",
49  pybind11::return_value_policy::automatic);
50  cl.def(
51  "serverHostAddress",
52  (void(mvsim::Client::*)(const std::string&)) & mvsim::Client::serverHostAddress,
53  "C++: mvsim::Client::serverHostAddress(const std::string &) --> "
54  "void",
55  pybind11::arg("serverIpOrAddressName"));
56  cl.def(
57  "connect", (void(mvsim::Client::*)()) & mvsim::Client::connect,
58  "Connects to the server in a parallel thread.\n Default server "
59  "address is `localhost`, can be changed with\n "
60  "serverHostAddress().\n\nC++: mvsim::Client::connect() --> void");
61  cl.def(
62  "connected", (bool(mvsim::Client::*)() const) & mvsim::Client::connected,
63  "Whether the client is correctly connected to the server. \n\nC++: "
64  "mvsim::Client::connected() const --> bool");
65  cl.def(
66  "shutdown", (void(mvsim::Client::*)()) & mvsim::Client::shutdown,
67  "Shutdowns the communication thread. Blocks until the thread is "
68  "stopped.\n There is no need to manually call this method, it is "
69  "called upon\n destruction. \n\nC++: mvsim::Client::shutdown() --> "
70  "void");
71  cl.def(
72  "callService",
73  (std::string(mvsim::Client::*)(const std::string&, const std::string&)) &
75  "Overload for python wrapper\n\nC++: "
76  "mvsim::Client::callService(const std::string &, const std::string "
77  "&) --> std::string",
78  pybind11::arg("serviceName"), pybind11::arg("inputSerializedMsg"));
79  cl.def(
80  "subscribeTopic",
81  (void(mvsim::Client::*)(
82  const std::string&,
83  const class std::function<void(
84  const std::string&,
85  const class std::vector<
86  unsigned char, class std::allocator<unsigned char>>&)>&)) &
88  "Overload for python wrapper (callback accepts "
89  "bytes-string)\n\nC++: mvsim::Client::subscribeTopic(const "
90  "std::string &, const class std::function<void (const std::string "
91  "&, const class std::vector<unsigned char, class "
92  "std::allocator<unsigned char> > &)> &) --> void",
93  pybind11::arg("topicName"), pybind11::arg("callback"));
94  cl.def(
95  "enable_profiler", (void(mvsim::Client::*)(bool)) & mvsim::Client::enable_profiler,
96  "C++: mvsim::Client::enable_profiler(bool) --> void", pybind11::arg("enable"));
97 
98  { // mvsim::Client::InfoPerNode file:mvsim/Comms/Client.h line:113
99  auto& enclosing_class = cl;
100  pybind11::class_<
101  mvsim::Client::InfoPerNode, std::shared_ptr<mvsim::Client::InfoPerNode>>
102  cl(enclosing_class, "InfoPerNode", "");
103  cl.def(pybind11::init([]() { return new mvsim::Client::InfoPerNode(); }));
104  cl.def(pybind11::init([](mvsim::Client::InfoPerNode const& o)
105  { return new mvsim::Client::InfoPerNode(o); }));
106  cl.def_readwrite("name", &mvsim::Client::InfoPerNode::name);
107  cl.def(
108  "assign",
111  mvsim::Client::InfoPerNode::operator=,
112  "C++: mvsim::Client::InfoPerNode::operator=(const struct "
113  "mvsim::Client::InfoPerNode &) --> struct "
114  "mvsim::Client::InfoPerNode &",
115  pybind11::return_value_policy::automatic, pybind11::arg(""));
116  }
117 
118  { // mvsim::Client::InfoPerTopic file:mvsim/Comms/Client.h line:119
119  auto& enclosing_class = cl;
120  pybind11::class_<
121  mvsim::Client::InfoPerTopic, std::shared_ptr<mvsim::Client::InfoPerTopic>>
122  cl(enclosing_class, "InfoPerTopic", "");
123  cl.def(pybind11::init([]() { return new mvsim::Client::InfoPerTopic(); }));
124  cl.def(pybind11::init([](mvsim::Client::InfoPerTopic const& o)
125  { return new mvsim::Client::InfoPerTopic(o); }));
126  cl.def_readwrite("name", &mvsim::Client::InfoPerTopic::name);
127  cl.def_readwrite("type", &mvsim::Client::InfoPerTopic::type);
128  cl.def_readwrite("endpoints", &mvsim::Client::InfoPerTopic::endpoints);
129  cl.def_readwrite("publishers", &mvsim::Client::InfoPerTopic::publishers);
130  cl.def(
131  "assign",
134  mvsim::Client::InfoPerTopic::operator=,
135  "C++: mvsim::Client::InfoPerTopic::operator=(const struct "
136  "mvsim::Client::InfoPerTopic &) --> struct "
137  "mvsim::Client::InfoPerTopic &",
138  pybind11::return_value_policy::automatic, pybind11::arg(""));
139  }
140  }
141 }
Client.h
mvsim::Client::connected
bool connected() const
Definition: src/Comms/Client.cpp:129
mvsim::Client::subscribeTopic
void subscribeTopic(const std::string &topicName, const std::function< void(const MSG_T &)> &callback)
Definition: Client.h:198
mvsim::Client::serverHostAddress
const std::string & serverHostAddress() const
Definition: Client.h:60
mvsim::Client::InfoPerTopic::publishers
std::vector< std::string > publishers
Definition: Client.h:119
mvsim::Client
Definition: Client.h:48
mvsim::Client::InfoPerNode
Definition: Client.h:109
std::allocator
mvsim::Client::InfoPerTopic::endpoints
std::vector< std::string > endpoints
Definition: Client.h:119
mvsim::Client::connect
void connect()
Definition: src/Comms/Client.cpp:138
mvsim::Client::setName
void setName(const std::string &nodeName)
Definition: src/Comms/Client.cpp:127
mvsim::Client::InfoPerTopic::name
std::string name
Definition: Client.h:117
mvsim::Client::InfoPerTopic::type
std::string type
Definition: Client.h:118
mvsim::Client::enable_profiler
void enable_profiler(bool enable)
Definition: Client.h:130
mvsim::Client::shutdown
void shutdown() noexcept
Definition: src/Comms/Client.cpp:196
mvsim::Client::InfoPerNode::name
std::string name
Definition: Client.h:111
bind_mvsim_Comms_Client
void bind_mvsim_Comms_Client(std::function< pybind11::module &(std::string const &namespace_)> &M)
Definition: python/generated-sources-pybind/mvsim/Comms/Client.cpp:21
mvsim::Client::callService
void callService(const std::string &serviceName, const INPUT_MSG_T &input, OUTPUT_MSG_T &output)
Definition: Client.h:213
mvsim::Client::InfoPerTopic
Definition: Client.h:115


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