Plugin
For incorporating advanced features like state estimation and mapping, Raisin supports the use of plugins. These plugins are dynamically loaded and the advance()
function is called periodically according to the specified frequency (Hz). There are three methods to load a plugin:
Load by
raisin_raibo2_node
: This method loads the plugin from the start of the executable.Load by
controller
: This method loads the plugin concurrently when the controller is loaded.Load by
plugin
: This method loads other plugin concurrently when the plugin is loaded.
To load a plugin, details such as the plugin name and the desired frequency of updates must be specified in the params.yaml file located under the config
directory of the package. Here’s how you can declare it in the params.yaml
file:
plugin:
raisin_foo: # plugin package name
rate:
value: 200 # loop frequency
dtype: double
raisin_bar:
rate:
value: 300
dtype: double
In this configuration:
name: Specifies the unique identifier or name of the plugin.
frequency: Specifies how often, in Hertz (Hz), the
advance()
function of the plugin should be called.
A plugin stores its subscribers, which are packages(can be raibo_node
, controller
, and plugin
) that configured the plugin.
A plugin is unloaded if
There’s no subscriber anymore
Another plugin with same pluginType is loaded(refer to the
PluginType
)
For implementing plugins in Raisin, it’s important to adhere to the naming convention specified. Each plugin should be named following the pattern raisin_**_plugin
, where ** represents a descriptive part of the plugin’s functionality.
For practical implementation examples, refer to the raisin_example_plugin.zip
.
API
-
class PluginManager : public Node
Public Functions
-
bool load(const std::string &plugin_name, double frequency, std::string subscribe)
- Parameters:
plugin_name – name to the state estimator dynamic library (must be same as the ros package name)
-
template<typename T>
inline T *getPlugin(const std::string &plugin_name) - Parameters:
plugin_name – identical to the package name
- Returns:
casted Plugin
-
Plugin *getPlugin(const std::string &plugin_name)
- Parameters:
plugin_name – identical to the package name
- Returns:
-
bool hasPlugin(const std::string &plugin_name)
- Parameters:
plugin_name – identical to the package name
- Returns:
whether the PluginManager holds the Plugin
-
bool load(const std::string &plugin_name, double frequency, std::string subscribe)
-
class Plugin
Plugin class to control a robot.
To implement your own Plugin, inherit this class and implement virtual methods.
worldHub_ holds the robot’s estimated state and environment(including height), which are set by plugins.
Inside worldHub_, robotHub_ offers sensor data access (encoders, cameras, IMUs) and allows for issuing torque commands.
Note: worldSim_ is solely for simulations and must not be used with actual robots.
Estimated world(worldHub_) is visualized in serverHub_ (port 8080), and simulated world(worldSim_) is visualized in serverSim_ (port 7000).
Public Functions
-
inline explicit Plugin(raisim::World &worldHub, raisim::RaisimServer &serverHub, raisim::World &worldSim, raisim::RaisimServer &serverSim, GlobalResource &globalResource)
- Parameters:
name – name of the plugin
world – see worldHub_
server – see serverHub_
worldSim – see worldSim_
serverSim – see serverSim_
globalResource – global resources such as paramRoot, dataLogger
-
inline virtual bool init()
initialize plugin. this is called only once.
- Returns:
true if successful
-
inline virtual bool advance()
advance plugin. This is called regularly by PluginManager. robot’s state, or estimated environment should be updated.
- Returns:
true if successful
-
inline virtual bool reset()
reset plugin
- Returns:
true if successful
-
inline PluginType getPluginType()
check PluginType.
- Returns:
Protected Attributes
-
PluginType pluginType_
check PluginType.
-
raisim::World &worldHub_
The worldHub_ object holds the robot’s estimated state and environment(including height), which are set by plugins. Through this variable, you can
1) set the estimated environment(addHeightMap…)
2) get the world time (getWolrdTime)
-
raisim::RaisimServer &serverHub_
This is for visualization of worldHub_ in port 8080. You can add visualObject through this serverHub_.
-
raisim::ArticulatedSystem *robotHub_
ArticulatedSystem variable that holds the information about the robot. This is member of worldHub_. Through this variable, you can
set the estimated robot’s state(setGeneralizedCoordinate, setGeneralizedVelocity…)
get the estimated robot’s state(getGeneralizedCoordinate, getGeneralizedVelocity…)
-
raisim::ArticulatedSystem *robotSim_
ArticulatedSystem variable that holds the information about the robot in the simulation. This is member of worldSim_. Through this variable, you can
set the estimated robot’s state(setGeneralizedCoordinate, setGeneralizedVelocity…)
get the estimated robot’s state(getGeneralizedCoordinate, getGeneralizedVelocity…)
-
raisim::World &worldSim_
worldSim_ is solely for simulations and must not be used with actual robots. You can get ground truth information of simulation through worldSim_.
-
raisim::RaisimServer &serverSim_
This is for visualization of worldSim_, and simulated camera streaming in port 7000. If you want to use camera, make sure to turn on raisimUnreal on port 7000.
-
raisin::parameter::ParameterContainer ¶mRoot_
Use this variable instead of calling parameter::ParameterContainer::getRoot(), which is not valid in dynamic library.
-
raisin::DataLogger &dataLogger_
Use this variable instead of calling “raisin::DataLogger raisin::DataLogger::getInstance() = raisin::DataLogger()”, which is not valid in dynamic library.
-
size_t logIdx_
Initialize this with DataLogger::initializeAnotherDataGroup.
-
std::vector<Plugin*> postPlugins_
all postPlugin->advance() is called for after this->advance() is called
-
std::atomic_bool terminate_ = {false}
If this becomes false, PluginManager stops calling advance(), and destroy Plugin.
- Return:
wheter the plugin is terminated
-
inline explicit Plugin(raisim::World &worldHub, raisim::RaisimServer &serverHub, raisim::World &worldSim, raisim::RaisimServer &serverSim, GlobalResource &globalResource)
-
enum raisin::plugin::PluginType
PluginType specifies the function of Plugin.
Because the plugins of the same type can potentially conflict with each other, PluginManager unload the existing plugin of the same type when loading one.
The user should specify the Plugin::pluginType_ in the Plugin’s constructor, such as
pluginType_ = PluginType::STATE_ESTIMATOR
.If a SLAM plugin is loaded, the existing state estimator and mapping plugins are additionally unloaded.
To allow multiple Plugin of the same type, set
pluginType_ = PluginType::CUSTOM
.Values:
-
enumerator CUSTOM
multiple plugin with this type can be used
-
enumerator STATE_ESTIMATOR
state estimator
-
enumerator MAPPING
mapping
-
enumerator SLAM
both state estimator and mapping
-
enumerator CUSTOM