Manages communication with the NRP. More...
#include <nrp_communication_controller.h>
Public Types | |
using | mutex_t = std::timed_mutex |
using | lock_t = std::unique_lock< NRPGazeboCommunicationController::mutex_t > |
![]() | |
using | mutex_t = std::timed_mutex |
using | lock_t = std::unique_lock< EngineProtoWrapper::mutex_t > |
Public Member Functions | |
NRPGazeboCommunicationController (const std::string &engineName, const std::string &protobufPluginsPath, const nlohmann::json &protobufPlugins) | |
void | registerDataPackWithLock (const std::string &datapackName, ProtoDataPackController *interface) |
Registers a datapack controller locking the datapack mutex. More... | |
void | registerStepController (GazeboStepController *stepController) |
Register a step controller. More... | |
void | registerSensorPlugin (gazebo::SensorPlugin *sensorPlugin) |
Register a sensor plugin. More... | |
void | registerModelPlugin (gazebo::ModelPlugin *modelPlugin) |
Register a model plugin. More... | |
SimulationTime | runLoopStep (SimulationTime timeStep) override |
Runs a single simulation loop step. More... | |
void | initialize (const nlohmann::json &data) override |
Initializes the simulation. More... | |
void | reset () override |
Resets the simulation. More... | |
void | shutdown () override |
Shutdowns the simulation. More... | |
bool | initRunFlag () const override |
Indicates if the simulation was initialized and is running. More... | |
bool | shutdownFlag () const override |
Indicates if shutdown was requested by the client. More... | |
![]() | |
EngineProtoWrapper ()=delete | |
No dummy wrappers, only those with name. More... | |
EngineProtoWrapper (const std::string &engineName, const std::string &protobufPluginsPath, const nlohmann::json &protobufPlugins) | |
Constructor. More... | |
virtual | ~EngineProtoWrapper ()=default |
Destructor. More... | |
void | registerDataPack (const std::string &datapackName, ProtoDataPackController *interface) |
Registers a datapack controller with the given name in the engine. More... | |
unsigned | getNumRegisteredDataPacks () |
std::vector< std::string > | getNamesRegisteredDataPacks () |
Get the names of registered datapacks. More... | |
const std::string & | getEngineName () |
Get the Engine name. More... | |
void | setDataPacks (const EngineGrpc::SetDataPacksRequest &data) |
void | setDataPack (const EngineGrpc::DataPackMessage &dataPack) |
std::unique_ptr< gpb::Message > | unpackFromAny (const gpb::Any &data) |
virtual void | getDataPacks (const EngineGrpc::GetDataPacksRequest &request, EngineGrpc::GetDataPacksReply *reply) |
bool | getDataPack (const std::string &name, EngineGrpc::DataPackMessage *dpMsg) |
void | setDataPackMessageData (gpb::Message *data, EngineGrpc::DataPackMessage *dpMsg) |
Static Public Member Functions | |
static std::string | createDataPackName (const std::string &modelName, const std::string &objectName) |
Create datapack name from the given plugin and sensor/joint/link. More... | |
Additional Inherited Members | |
![]() | |
void | clearRegisteredDataPacks () |
ProtoDataPackController * | getDataPackController (const std::string &datapackName) |
Returns the pointer to the DataPackController of the Data Pack with the specified name. More... | |
![]() | |
bool | _handleDataPackMessage = false |
If true controllers are sent incoming DataPackMessages, if false only the contained data. More... | |
std::vector< std::unique_ptr< protobuf_ops::NRPProtobufOpsIface > > | _protoOps |
std::string | _protoOpsStr = "" |
Manages communication with the NRP.
Implementation of EngineProtoWrapper to manage a Gazebo Engine
using NRPGazeboCommunicationController::lock_t = std::unique_lock<NRPGazeboCommunicationController::mutex_t> |
using NRPGazeboCommunicationController::mutex_t = std::timed_mutex |
NRPGazeboCommunicationController::NRPGazeboCommunicationController | ( | const std::string & | engineName, |
const std::string & | protobufPluginsPath, | ||
const nlohmann::json & | protobufPlugins | ||
) |
|
inlinestatic |
Create datapack name from the given plugin and sensor/joint/link.
modelName | Name of the parent model of the controlled object |
objectName | Name of the controlled object (sensor, joint, link, ...) |
|
overridevirtual |
Initializes the simulation.
[in] | data | Simulation configuration data |
[in] | datapackLock | ??? |
Implements EngineProtoWrapper.
|
inlineoverridevirtual |
Indicates if the simulation was initialized and is running.
Implements EngineProtoWrapper.
|
inline |
Registers a datapack controller locking the datapack mutex.
[in] | datapackName | Name of the datapack to be registered |
[in] | datapackController | Pointer to the datapack controller object that's supposed to be registered in the engine |
|
inline |
Register a model plugin.
sensorPlugin | Pointer to model plugin |
|
inline |
Register a sensor plugin.
sensorPlugin | Pointer to sensor plugin |
void NRPGazeboCommunicationController::registerStepController | ( | GazeboStepController * | stepController | ) |
Register a step controller.
stepController | Pointer to step controller |
|
overridevirtual |
Resets the simulation.
Implements EngineProtoWrapper.
|
overridevirtual |
Runs a single simulation loop step.
[in] | timeStep | Time step by which the simulation should be advanced |
Implements EngineProtoWrapper.
|
overridevirtual |
Shutdowns the simulation.
Implements EngineProtoWrapper.
|
inlineoverridevirtual |
Indicates if shutdown was requested by the client.
Implements EngineProtoWrapper.