7 #include <pybind11/pybind11.h> 10 #include <pybind11/stl.h> 13 #ifndef BINDER_PYBIND11_TYPE_CASTER 14 #define BINDER_PYBIND11_TYPE_CASTER 23 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 ");
25 auto & enclosing_class = cl;
26 pybind11::class_<mvsim::Client::InfoPerNode, std::shared_ptr<mvsim::Client::InfoPerNode>> cl(enclosing_class,
"InfoPerNode",
"");
33 auto & enclosing_class = cl;
34 pybind11::class_<mvsim::Client::InfoPerTopic, std::shared_ptr<mvsim::Client::InfoPerTopic>> cl(enclosing_class,
"InfoPerTopic",
"");
43 cl.def( pybind11::init( [](){
return new mvsim::Client(); } ) );
44 cl.def( pybind11::init<const std::string &>(), pybind11::arg(
"nodeName") );
46 cl.def(
"setName", (
void (
mvsim::Client::*)(
const std::string &)) &
mvsim::Client::setName,
"@{ \n\nC++: mvsim::Client::setName(const std::string &) --> void", pybind11::arg(
"nodeName"));
48 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");
49 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");
50 cl.def(
"callService", (std::string (
mvsim::Client::*)(
const std::string &,
const std::string &)) &
mvsim::Client::callService,
"C++: mvsim::Client::callService(const std::string &, const std::string &) --> std::string", pybind11::arg(
"serviceName"), pybind11::arg(
"inputSerializedMsg"));
std::vector< std::string > endpoints
void setName(const std::string &nodeName)
PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr< T >)
void callService(const std::string &serviceName, const INPUT_MSG_T &input, OUTPUT_MSG_T &output)
void bind_mvsim_Comms_Client(std::function< pybind11::module &(std::string const &namespace_) > &M)
PYBIND11_MAKE_OPAQUE(std::shared_ptr< void >)
std::vector< std::string > publishers