VNX Interface ============= The native VNX binary protocol allows to communicate with the `PlatformPilot` in a C++ application, either via TCP/IP, UNIX socket or a direct intra-procress connection. The communication is provided via the :ref:`vnx.Server` and :ref:`vnx.Proxy` modules. Server ------ To enable a :ref:`vnx.Server` create a config file ``config/local/vnx_server_map``: .. code-block:: javascript [ ["TcpServer_1", "0.0.0.0:1234"], ["UnixServer_1", "/tmp/mysocket.sock"] ] This will start two VNX servers listening on TCP/IP address ``0.0.0.0:1234`` and UNIX socket ``/tmp/mysocket.sock`` respectively. By default a VNX server is listening on TCP/IP address ``0.0.0.0:5555``, which requires a login for most funtionality. To enable user authentication, which is recommended for TCP/IP servers, create a config file ``config/local/TcpServer_1.json``: .. code-block:: javascript { "use_authentication": true, "default_access": "OBSERVER" } This will require a login to gain more than the ``default_access`` permissions. If ``use_authentication`` is set to ``false`` any user has full permissions and no login is necessary. Proxy ----- To run a :ref:`vnx.Proxy` which connects to another VNX server create a config file ``vnx_proxy_map`` which is used by your process: .. code-block:: javascript [ ["Proxy_1", "127.0.0.1:5555"], ["Proxy_2", "/tmp/mysocket.sock"] ] The above proxies will be available under the module names ``Proxy_1`` and ``Proxy_2``. To import / export topics and forward services create a config file for each proxy. For example ``Proxy_1.json``: .. code-block:: javascript { "import_list": [ "input", "sensors.raw_data", "platform.system_state", "platform.battery_state", "platform.emergency_state", "kinematics.drive_state" ], "export_list": [ "platform.drive_cmd", ], "forward_list": [ "PlatformInterface" ], "time_sync": true } To gain required permissions a login needs to be performed at runtime: .. code-block:: cpp #include #include std::string user; if(vnx::read_config("user", user)) { vnx::ProxyClient proxy("Proxy"); proxy.login(user, vnx::input_password("Password: ")); } Clients ------- A `Client` is a way to communicate with a module via (remote) procedure calls. Synchronization ^^^^^^^^^^^^^^^ There are synchronous clients and asynchronous clients. A method call on a synchronous client blocks until the result arrives. A method call on an asynchronous client returns immediately and gives you the possibility to supply callback functions that notify you about the result. Specific Clients ^^^^^^^^^^^^^^^^ Every module has a synchronous and an asynchronous client. If the module class is called ``MyModule``, the clients are called ``MyModuleClient`` and ``MyModuleAsyncClient``. In order to instantiate them, you also need to know the runtime name of the module (not the name of the class). Here is an example on how to use the clients for ``MyModule`` that is running under the name ``MyModule_name`` to call its method ``void do_something(int, string)``. .. code-block:: cpp #include #include using namespace package; MyModuleClient sync_client("MyModule_name"); sync_client.do_something(42, "hello"); std::shared_ptr async_client = std::make_shared("MyModule_name"); add_async_client(async_client); async_client->do_something(42, "hello", [](void) { std::cout << "OK" << std::endl; }, [](const vnx::exception& ex) { std::cout << "FAIL: " << ex.what() << std::endl; } ); The callback functions for asynchronous clients are of the forms ``void(const T&)`` (where `T` is the return type, or `void`) and ``void(const vnx::exception&)`` respectively. Supplying either of them is optional and defaults to a null function. Generic Clients ^^^^^^^^^^^^^^^ With a generic client, you can communicate with any module. The handling is similar to the specific case, only this time you call methods by their name and supply the parameters as a :ref:`vnx.Object`. The names of the method and the parameters have to match the interface definition. .. code-block:: cpp #include vnx::Object args; args["number"] = 42; args["message"] = "hello"); vnx::GenericClient sync_client("MyModule_name"); std::shared_ptr ret = sync_client.call("do_something", args); std::cout << "OK: " << ret->get_field_by_index(0) << std::endl; std::shared_ptr async_client = std::make_shared("MyModule_name"); add_async_client(async_client); async_client->call("do_something", args, [](std::shared_ptr ret) { std::cout << "OK: " << ret->get_field_by_index(0) << std::endl; }, [](const vnx::exception& ex) { std::cout << "FAIL: " << ex.what() << std::endl; } ); The callback functions are of the form ``void(std::shared_ptr)`` and ``void(const vnx::exception&)`` respectively. Supplying either of them is optional and defaults to a null function. Compiling --------- Example on how to compile your C++ application: .. code-block:: sh g++ -std=c++11 application.cpp -I /opt/neobotix/pilot-core/include \ -L /opt/neobotix/pilot-core/lib -lpilot_core -lvnx_base ``/opt/neobotix/pilot-core`` can also be replaced by ``/opt/neobotix/pilot-gtkgui``, if you have the :ref:`GTKGUI` installed. Example ------- Connecting to the `PlatformPilot` and sending goals to :ref:`HybridPlanner`. ``config/default/vnx_proxy_map``: .. code-block:: javascript [["Proxy", ""]] We do not specify an address in the config above, since we want to give a custom address on the command line later. ``config/default/Proxy.json``: .. code-block:: javascript {"forward_list": ["HybridPlanner"]} ``move_to_stations.cpp``: .. literalinclude:: ../../examples/src/move_to_stations.cpp :tab-width: 4 :language: cpp Compiling: .. code-block:: sh g++ -std=c++11 -o move_to_stations move_to_stations.cpp \ -I /opt/neobotix/pilot-core/include \ -L /opt/neobotix/pilot-core/lib -lpilot_core -lvnx_base Running: .. code-block:: sh $ ./move_to_stations -c config/default/ --Proxy.address ~/pilot/.pilot_main.sock Proxy.address = "/home/neobotix/pilot/.pilot_main.sock" Proxy.forward_list = ["HybridPlanner"] config = ["config/default/"] vnx_proxy_map = [["Proxy", ""]] [Proxy] INFO: enable_forward('HybridPlanner', 100, 1000) [Proxy] INFO: Connected to /home/neobotix/pilot/.pilot_main.sock [move_to_stations] INFO: Station1 has been reached! [move_to_stations] INFO: Station2 has been reached! [move_to_stations] INFO: Station3 has been reached! (job 13373535902967275021) ... Connecting to ``.pilot_main.sock`` avoids having to login with a username and password to be able to move the platform.