NRP Core  1.4.1
NRPGazeboCommunicationController Class Reference

Manages communication with the NRP. More...

#include <nrp_communication_controller.h>

Inheritance diagram for NRPGazeboCommunicationController:
EngineProtoWrapper

Public Types

using mutex_t = std::timed_mutex
 
using lock_t = std::unique_lock< NRPGazeboCommunicationController::mutex_t >
 
- Public Types inherited from EngineProtoWrapper
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...
 
- Public Member Functions inherited from EngineProtoWrapper
 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

- Protected Member Functions inherited from EngineProtoWrapper
void clearRegisteredDataPacks ()
 
ProtoDataPackControllergetDataPackController (const std::string &datapackName)
 Returns the pointer to the DataPackController of the Data Pack with the specified name. More...
 
- Protected Attributes inherited from EngineProtoWrapper
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 = ""
 

Detailed Description

Manages communication with the NRP.

Implementation of EngineProtoWrapper to manage a Gazebo Engine

Member Typedef Documentation

◆ lock_t

◆ mutex_t

Constructor & Destructor Documentation

◆ NRPGazeboCommunicationController()

NRPGazeboCommunicationController::NRPGazeboCommunicationController ( const std::string &  engineName,
const std::string &  protobufPluginsPath,
const nlohmann::json protobufPlugins 
)

Member Function Documentation

◆ createDataPackName()

static std::string NRPGazeboCommunicationController::createDataPackName ( const std::string &  modelName,
const std::string &  objectName 
)
inlinestatic

Create datapack name from the given plugin and sensor/joint/link.

Parameters
modelNameName of the parent model of the controlled object
objectNameName of the controlled object (sensor, joint, link, ...)
Returns
Returns datapack name

◆ initialize()

void NRPGazeboCommunicationController::initialize ( const nlohmann::json data)
overridevirtual

Initializes the simulation.

Parameters
[in]dataSimulation configuration data
[in]datapackLock???

Implements EngineProtoWrapper.

◆ initRunFlag()

bool NRPGazeboCommunicationController::initRunFlag ( ) const
inlineoverridevirtual

Indicates if the simulation was initialized and is running.

Implements EngineProtoWrapper.

◆ registerDataPackWithLock()

void NRPGazeboCommunicationController::registerDataPackWithLock ( const std::string &  datapackName,
ProtoDataPackController interface 
)
inline

Registers a datapack controller locking the datapack mutex.

Parameters
[in]datapackNameName of the datapack to be registered
[in]datapackControllerPointer to the datapack controller object that's supposed to be registered in the engine

◆ registerModelPlugin()

void NRPGazeboCommunicationController::registerModelPlugin ( gazebo::ModelPlugin *  modelPlugin)
inline

Register a model plugin.

Parameters
sensorPluginPointer to model plugin

◆ registerSensorPlugin()

void NRPGazeboCommunicationController::registerSensorPlugin ( gazebo::SensorPlugin *  sensorPlugin)
inline

Register a sensor plugin.

Parameters
sensorPluginPointer to sensor plugin

◆ registerStepController()

void NRPGazeboCommunicationController::registerStepController ( GazeboStepController stepController)

Register a step controller.

Parameters
stepControllerPointer to step controller

◆ reset()

void NRPGazeboCommunicationController::reset ( )
overridevirtual

Resets the simulation.

Implements EngineProtoWrapper.

◆ runLoopStep()

SimulationTime NRPGazeboCommunicationController::runLoopStep ( SimulationTime  timeStep)
overridevirtual

Runs a single simulation loop step.

Parameters
[in]timeStepTime step by which the simulation should be advanced
Returns
Engine time after running the step

Implements EngineProtoWrapper.

◆ shutdown()

void NRPGazeboCommunicationController::shutdown ( )
overridevirtual

Shutdowns the simulation.

Implements EngineProtoWrapper.

◆ shutdownFlag()

bool NRPGazeboCommunicationController::shutdownFlag ( ) const
inlineoverridevirtual

Indicates if shutdown was requested by the client.

Implements EngineProtoWrapper.


The documentation for this class was generated from the following files: