1 #include <mrpt/system/CTimeLogger.h> 3 #include <pybind11/functional.h> 4 #include <pybind11/pybind11.h> 5 #include <pybind11/stl.h> 12 #include <string_view> 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>)
22 std::function<pybind11::module&(std::string
const& namespace_)>& M)
25 pybind11::class_<mvsim::Client, std::shared_ptr<mvsim::Client>> cl(
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 " 39 cl.def(pybind11::init<const std::string&>(), pybind11::arg(
"nodeName"));
45 "@{ \n\nC++: mvsim::Client::setName(const std::string &) --> void",
46 pybind11::arg(
"nodeName"));
51 "C++: mvsim::Client::serverHostAddress() const --> const " 53 pybind11::return_value_policy::automatic);
58 "C++: mvsim::Client::serverHostAddress(const std::string &) --> " 60 pybind11::arg(
"serverIpOrAddressName"));
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");
69 "Whether the client is correctly connected to the server. \n\nC++: " 70 "mvsim::Client::connected() const --> bool");
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() --> " 80 const std::string&,
const std::string&)) &
82 "Overload for python wrapper\n\nC++: " 83 "mvsim::Client::callService(const std::string &, const std::string " 85 pybind11::arg(
"serviceName"), pybind11::arg(
"inputSerializedMsg"));
90 const class std::function<
void(
92 const class std::vector<
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"));
105 "C++: mvsim::Client::enable_profiler(bool) --> void",
106 pybind11::arg(
"enable"));
109 auto& enclosing_class = cl;
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);
122 (
struct mvsim::Client::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(
""));
133 auto& enclosing_class = cl;
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);
151 (
struct mvsim::Client::InfoPerTopic &
152 (mvsim::Client::InfoPerTopic::*)(
const struct mvsim::Client::
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(
""));
std::vector< std::string > endpoints
void enable_profiler(bool enable)
void setName(const std::string &nodeName)
void subscribeTopic(const std::string &topicName, const std::function< void(const MSG_T &)> &callback)
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)
const std::string & serverHostAddress() const
std::vector< std::string > publishers