Skip to content

Commit

Permalink
regenerate python bindings
Browse files Browse the repository at this point in the history
  • Loading branch information
Aposhian committed Jan 16, 2025
1 parent 9888216 commit fe7775b
Show file tree
Hide file tree
Showing 5 changed files with 58 additions and 83 deletions.
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
#include <mrpt/system/CTimeLogger.h>
#include <mvsim/Comms/Client.h>
#include <pybind11/functional.h>
#include <pybind11/pybind11.h>
#include <pybind11/stl.h>

Expand All @@ -13,27 +12,24 @@

#ifndef BINDER_PYBIND11_TYPE_CASTER
#define BINDER_PYBIND11_TYPE_CASTER
PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr<T>)
PYBIND11_DECLARE_HOLDER_TYPE(T, T*)
PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr<T>, false)
PYBIND11_DECLARE_HOLDER_TYPE(T, T*, false)
PYBIND11_MAKE_OPAQUE(std::shared_ptr<void>)
#endif

void bind_mvsim_Comms_Client(std::function<pybind11::module&(std::string const& namespace_)>& M)
{
{ // mvsim::Client file:mvsim/Comms/Client.h line:48
{ // mvsim::Client file:mvsim/Comms/Client.h line:54
pybind11::class_<mvsim::Client, std::shared_ptr<mvsim::Client>> cl(
M("mvsim"), "Client",
"This is the connection of any user program with the MVSIM server, "
"so\n it can advertise and subscribe to topics and use remote "
"services.\n\n Users should instance a class mvsim::Client (C++) "
"or mvsim.Client (Python) to\n communicate with the simulation "
"runnin in mvsim::World or any other module.\n\n Usage:\n - "
"Instantiate a Client object.\n - Call connect(). It will return "
"immediately.\n - The client will be working on the background as "
"long as the object is not\n destroyed.\n\n Messages and topics "
"are described as Protobuf messages, and communications\n are done "
"via ZMQ sockets.\n\n See: https://mvsimulator.readthedocs.io/\n\n "
"\n\n ");
"This is the connection of any user program with the MVSIM server, so\n it can "
"advertise and subscribe to topics and use remote services.\n\n Users should instance "
"a class mvsim::Client (C++) or mvsim.Client (Python) to\n communicate with the "
"simulation runnin in mvsim::World or any other module.\n\n Usage:\n - Instantiate a "
"Client object.\n - Call connect(). It will return immediately.\n - The client will "
"be working on the background as long as the object is not\n destroyed.\n\n Messages "
"and topics are described as Protobuf messages, and communications\n are done via ZMQ "
"sockets.\n\n See: https://mvsimulator.readthedocs.io/\n\n \n\n ");
cl.def(pybind11::init([]() { return new mvsim::Client(); }));
cl.def(pybind11::init<const std::string&>(), pybind11::arg("nodeName"));

Expand All @@ -44,58 +40,59 @@ void bind_mvsim_Comms_Client(std::function<pybind11::module&(std::string const&
cl.def(
"serverHostAddress",
(const std::string& (mvsim::Client::*)() const) & mvsim::Client::serverHostAddress,
"C++: mvsim::Client::serverHostAddress() const --> const "
"std::string &",
"C++: mvsim::Client::serverHostAddress() const --> const std::string &",
pybind11::return_value_policy::automatic);
cl.def(
"serverHostAddress",
(void(mvsim::Client::*)(const std::string&)) & mvsim::Client::serverHostAddress,
"C++: mvsim::Client::serverHostAddress(const std::string &) --> "
"void",
"C++: mvsim::Client::serverHostAddress(const std::string &) --> void",
pybind11::arg("serverIpOrAddressName"));
cl.def(
"connect", (void(mvsim::Client::*)()) & mvsim::Client::connect,
"Connects to the server in a parallel thread.\n Default server "
"address is `localhost`, can be changed with\n "
"serverHostAddress().\n\nC++: mvsim::Client::connect() --> void");
"Connects to the server in a parallel thread.\n Default server address is "
"`localhost`, can be changed with\n serverHostAddress().\n\nC++: "
"mvsim::Client::connect() --> void");
cl.def(
"connected", (bool(mvsim::Client::*)() const) & mvsim::Client::connected,
"Whether the client is correctly connected to the server. \n\nC++: "
"mvsim::Client::connected() const --> bool");
cl.def(
"shutdown", (void(mvsim::Client::*)()) & mvsim::Client::shutdown,
"Shutdowns the communication thread. Blocks until the thread is "
"stopped.\n There is no need to manually call this method, it is "
"called upon\n destruction. \n\nC++: mvsim::Client::shutdown() --> "
"void");
"Shutdowns the communication thread. Blocks until the thread is stopped.\n There is no "
"need to manually call this method, it is called upon\n destruction. \n\nC++: "
"mvsim::Client::shutdown() --> void");
cl.def(
"callService",
(std::string(mvsim::Client::*)(const std::string&, const std::string&)) &
(class pybind11::bytes(mvsim::Client::*)(const std::string&, const std::string&)) &
mvsim::Client::callService,
"Overload for python wrapper\n\nC++: "
"mvsim::Client::callService(const std::string &, const std::string "
"&) --> std::string",
"Overload for python wrapper\n\nC++: mvsim::Client::callService(const std::string &, "
"const std::string &) --> class pybind11::bytes",
pybind11::arg("serviceName"), pybind11::arg("inputSerializedMsg"));
cl.def(
"subscribeTopic",
(void(mvsim::Client::*)(
const std::string&,
const class std::function<void(
const std::string&,
const class std::vector<
unsigned char, class std::allocator<unsigned char>>&)>&)) &
const std::string&, const class std::vector<unsigned char>&)>&)) &
mvsim::Client::subscribeTopic,
"Overload for python wrapper (callback accepts "
"bytes-string)\n\nC++: mvsim::Client::subscribeTopic(const "
"std::string &, const class std::function<void (const std::string "
"&, const class std::vector<unsigned char, class "
"std::allocator<unsigned char> > &)> &) --> void",
"Overload for python wrapper (callback accepts bytes-string)\n\nC++: "
"mvsim::Client::subscribeTopic(const std::string &, const class std::function<void "
"(const std::string &, const class std::vector<unsigned char> &)> &) --> void",
pybind11::arg("topicName"), pybind11::arg("callback"));
cl.def(
"subscribe_topic_raw",
(void(mvsim::Client::*)(
const std::string&,
const class std::function<void(const class zmq::message_t&)>&)) &
mvsim::Client::subscribe_topic_raw,
"C++: mvsim::Client::subscribe_topic_raw(const std::string &, const class "
"std::function<void (const class zmq::message_t &)> &) --> void",
pybind11::arg("topicName"), pybind11::arg("callback"));
cl.def(
"enable_profiler", (void(mvsim::Client::*)(bool)) & mvsim::Client::enable_profiler,
"C++: mvsim::Client::enable_profiler(bool) --> void", pybind11::arg("enable"));

{ // mvsim::Client::InfoPerNode file:mvsim/Comms/Client.h line:113
{ // mvsim::Client::InfoPerNode file:mvsim/Comms/Client.h line:117
auto& enclosing_class = cl;
pybind11::class_<
mvsim::Client::InfoPerNode, std::shared_ptr<mvsim::Client::InfoPerNode>>
Expand All @@ -110,12 +107,11 @@ void bind_mvsim_Comms_Client(std::function<pybind11::module&(std::string const&
(mvsim::Client::InfoPerNode::*)(const struct mvsim::Client::InfoPerNode&)) &
mvsim::Client::InfoPerNode::operator=,
"C++: mvsim::Client::InfoPerNode::operator=(const struct "
"mvsim::Client::InfoPerNode &) --> struct "
"mvsim::Client::InfoPerNode &",
"mvsim::Client::InfoPerNode &) --> struct mvsim::Client::InfoPerNode &",
pybind11::return_value_policy::automatic, pybind11::arg(""));
}

{ // mvsim::Client::InfoPerTopic file:mvsim/Comms/Client.h line:119
{ // mvsim::Client::InfoPerTopic file:mvsim/Comms/Client.h line:123
auto& enclosing_class = cl;
pybind11::class_<
mvsim::Client::InfoPerTopic, std::shared_ptr<mvsim::Client::InfoPerTopic>>
Expand All @@ -133,8 +129,7 @@ void bind_mvsim_Comms_Client(std::function<pybind11::module&(std::string const&
(mvsim::Client::InfoPerTopic::*)(const struct mvsim::Client::InfoPerTopic&)) &
mvsim::Client::InfoPerTopic::operator=,
"C++: mvsim::Client::InfoPerTopic::operator=(const struct "
"mvsim::Client::InfoPerTopic &) --> struct "
"mvsim::Client::InfoPerTopic &",
"mvsim::Client::InfoPerTopic &) --> struct mvsim::Client::InfoPerTopic &",
pybind11::return_value_policy::automatic, pybind11::arg(""));
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,12 +9,12 @@

#ifndef BINDER_PYBIND11_TYPE_CASTER
#define BINDER_PYBIND11_TYPE_CASTER
PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr<T>)
PYBIND11_DECLARE_HOLDER_TYPE(T, T*)
PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr<T>, false)
PYBIND11_DECLARE_HOLDER_TYPE(T, T*, false)
PYBIND11_MAKE_OPAQUE(std::shared_ptr<void>)
#endif

// mvsim::UnexpectedMessageException file:mvsim/Comms/common.h line:49
// mvsim::UnexpectedMessageException file:mvsim/Comms/common.h line:51
struct PyCallBack_mvsim_UnexpectedMessageException : public mvsim::UnexpectedMessageException
{
using mvsim::UnexpectedMessageException::UnexpectedMessageException;
Expand All @@ -29,24 +29,18 @@ struct PyCallBack_mvsim_UnexpectedMessageException : public mvsim::UnexpectedMes
auto o = overload.operator()<pybind11::return_value_policy::reference>();
if (pybind11::detail::cast_is_temporary_value_reference<const char*>::value)
{
// pybind11 <=2.4: overload_caster_t, otherwise: override_caster_t
#if (PYBIND11_MAJOR_VERSION == 2 && PYBIND11_MINOR_VERSION <= 4)
static pybind11::detail::overload_caster_t<const char*> caster;
#else
static pybind11::detail::override_caster_t<const char*> caster;
#endif
return pybind11::detail::cast_ref<const char*>(std::move(o), caster);
}
else
return pybind11::detail::cast_safe<const char*>(std::move(o));
return pybind11::detail::cast_safe<const char*>(std::move(o));
}
return runtime_error::what();
}
};

void bind_mvsim_Comms_common(std::function<pybind11::module&(std::string const& namespace_)>& M)
{
{ // mvsim::UnexpectedMessageException file:mvsim/Comms/common.h line:49
{ // mvsim::UnexpectedMessageException file:mvsim/Comms/common.h line:51
pybind11::class_<
mvsim::UnexpectedMessageException, std::shared_ptr<mvsim::UnexpectedMessageException>,
PyCallBack_mvsim_UnexpectedMessageException, std::runtime_error>
Expand All @@ -64,8 +58,7 @@ void bind_mvsim_Comms_common(std::function<pybind11::module&(std::string const&
UnexpectedMessageException&)) &
mvsim::UnexpectedMessageException::operator=,
"C++: mvsim::UnexpectedMessageException::operator=(const class "
"mvsim::UnexpectedMessageException &) --> class "
"mvsim::UnexpectedMessageException &",
"mvsim::UnexpectedMessageException &) --> class mvsim::UnexpectedMessageException &",
pybind11::return_value_policy::automatic, pybind11::arg(""));
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
#include <stdexcept>
#include <string>

typedef std::function<pybind11::module&(std::string const&)> ModuleGetter;
using ModuleGetter = std::function<pybind11::module&(std::string const&)>;

void bind_std_exception(std::function<pybind11::module&(std::string const& namespace_)>& M);
void bind_std_stdexcept(std::function<pybind11::module&(std::string const& namespace_)>& M);
Expand Down Expand Up @@ -42,16 +42,15 @@ PYBIND11_MODULE(pymvsim_comms, root_module)
if (std::find(reserved_python_words.begin(), reserved_python_words.end(), ns) ==
reserved_python_words.end())
return ns;
else
return ns + '_';
return ns + '_';
});

std::vector<std::pair<std::string, std::string>> sub_modules{
{"", "mvsim"},
{"", "std"},
};
for (auto& p : sub_modules)
modules[p.first.size() ? p.first + "::" + p.second : p.second] =
modules[p.first.empty() ? p.second : p.first + "::" + p.second] =
modules[p.first].def_submodule(
mangle_namespace_name(p.second).c_str(),
("Bindings for " + p.first + "::" + p.second + " namespace").c_str());
Expand Down
16 changes: 5 additions & 11 deletions modules/comms/python/generated-sources-pybind/std/exception.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,8 @@

#ifndef BINDER_PYBIND11_TYPE_CASTER
#define BINDER_PYBIND11_TYPE_CASTER
PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr<T>)
PYBIND11_DECLARE_HOLDER_TYPE(T, T*)
PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr<T>, false)
PYBIND11_DECLARE_HOLDER_TYPE(T, T*, false)
PYBIND11_MAKE_OPAQUE(std::shared_ptr<void>)
#endif

Expand All @@ -28,16 +28,10 @@ struct PyCallBack_std_exception : public std::exception
auto o = overload.operator()<pybind11::return_value_policy::reference>();
if (pybind11::detail::cast_is_temporary_value_reference<const char*>::value)
{
// pybind11 <=2.4: overload_caster_t, otherwise: override_caster_t
#if (PYBIND11_MAJOR_VERSION == 2 && PYBIND11_MINOR_VERSION <= 4)
static pybind11::detail::overload_caster_t<const char*> caster;
#else
static pybind11::detail::override_caster_t<const char*> caster;
#endif
return pybind11::detail::cast_ref<const char*>(std::move(o), caster);
}
else
return pybind11::detail::cast_safe<const char*>(std::move(o));
return pybind11::detail::cast_safe<const char*>(std::move(o));
}
return exception::what();
}
Expand All @@ -58,8 +52,8 @@ void bind_std_exception(std::function<pybind11::module&(std::string const& names
"assign",
(class std::exception & (std::exception::*)(const class std::exception&)) &
std::exception::operator=,
"C++: std::exception::operator=(const class std::exception &) --> "
"class std::exception &",
"C++: std::exception::operator=(const class std::exception &) --> class std::exception "
"&",
pybind11::return_value_policy::automatic, pybind11::arg(""));
cl.def(
"what", (const char* (std::exception::*)() const) & std::exception::what,
Expand Down
16 changes: 5 additions & 11 deletions modules/comms/python/generated-sources-pybind/std/stdexcept.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,8 @@

#ifndef BINDER_PYBIND11_TYPE_CASTER
#define BINDER_PYBIND11_TYPE_CASTER
PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr<T>)
PYBIND11_DECLARE_HOLDER_TYPE(T, T*)
PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr<T>, false)
PYBIND11_DECLARE_HOLDER_TYPE(T, T*, false)
PYBIND11_MAKE_OPAQUE(std::shared_ptr<void>)
#endif

Expand All @@ -30,16 +30,10 @@ struct PyCallBack_std_runtime_error : public std::runtime_error
auto o = overload.operator()<pybind11::return_value_policy::reference>();
if (pybind11::detail::cast_is_temporary_value_reference<const char*>::value)
{
// pybind11 <=2.4: overload_caster_t, otherwise: override_caster_t
#if (PYBIND11_MAJOR_VERSION == 2 && PYBIND11_MINOR_VERSION <= 4)
static pybind11::detail::overload_caster_t<const char*> caster;
#else
static pybind11::detail::override_caster_t<const char*> caster;
#endif
return pybind11::detail::cast_ref<const char*>(std::move(o), caster);
}
else
return pybind11::detail::cast_safe<const char*>(std::move(o));
return pybind11::detail::cast_safe<const char*>(std::move(o));
}
return runtime_error::what();
}
Expand All @@ -64,8 +58,8 @@ void bind_std_stdexcept(std::function<pybind11::module&(std::string const& names
"assign",
(class std::runtime_error & (std::runtime_error::*)(const class std::runtime_error&)) &
std::runtime_error::operator=,
"C++: std::runtime_error::operator=(const class std::runtime_error "
"&) --> class std::runtime_error &",
"C++: std::runtime_error::operator=(const class std::runtime_error &) --> class "
"std::runtime_error &",
pybind11::return_value_policy::automatic, pybind11::arg(""));
cl.def(
"what", (const char* (std::runtime_error::*)() const) & std::runtime_error::what,
Expand Down

0 comments on commit fe7775b

Please sign in to comment.