![]() |
ORCA: Optimization-based framework for Robotic Control Applications
|
ParameterBase is the public interface to any parameter. More...
#include <ParameterBase.h>
Public Types | |
using | Ptr = std::shared_ptr< ParameterBase > |
Public Member Functions | |
virtual | ~ParameterBase () |
bool | loadFromString (const std::string &s) |
Load the parameter from a YAML string It calls a callback on success. More... | |
virtual void | print () const =0 |
virtual bool | isSet () const =0 |
const std::string & | getName () const |
void | setName (const std::string &name) |
void | setRequired (bool is_required) |
bool | isRequired () const |
void | onSuccess (std::function< void(void)> f) |
The callback called if loadFromString is successful. More... | |
Protected Member Functions | |
virtual bool | onLoadFromString (const std::string &s)=0 |
ParameterBase is the public interface to any parameter.
using orca::common::ParameterBase::Ptr = std::shared_ptr<ParameterBase> |
|
inlinevirtual |
|
inline |
|
inline |
|
pure virtual |
Implemented in orca::common::Parameter< std::list< T > >, orca::common::Parameter< T >, orca::common::Parameter< double >, orca::common::Parameter< Vector6d >, orca::common::Parameter< std::string >, orca::common::Parameter< int >, orca::common::Parameter< ResolutionStrategy >, orca::common::Parameter< math::Vector6d >, orca::common::Parameter< orca::common::PIDController::Ptr >, orca::common::Parameter< std::shared_ptr< common::CartesianServoController > >, orca::common::Parameter< std::list< task::GenericTask::Ptr > >, orca::common::Parameter< bool >, orca::common::Parameter< QPSolverImplType >, orca::common::Parameter< Eigen::VectorXd >, orca::common::Parameter< Eigen::Vector3d >, orca::common::Parameter< std::list< constraint::GenericConstraint::Ptr > >, orca::common::Parameter< robot::RobotModel::Ptr >, orca::common::Parameter< common::PIDController::Ptr >, and orca::common::Parameter< std::shared_ptr< T > >.
|
inline |
Load the parameter from a YAML string It calls a callback on success.
|
protectedpure virtual |
Implemented in orca::common::Parameter< std::list< T > >, orca::common::Parameter< T >, orca::common::Parameter< double >, orca::common::Parameter< Vector6d >, orca::common::Parameter< std::string >, orca::common::Parameter< int >, orca::common::Parameter< ResolutionStrategy >, orca::common::Parameter< math::Vector6d >, orca::common::Parameter< orca::common::PIDController::Ptr >, orca::common::Parameter< std::shared_ptr< common::CartesianServoController > >, orca::common::Parameter< std::list< task::GenericTask::Ptr > >, orca::common::Parameter< bool >, orca::common::Parameter< QPSolverImplType >, orca::common::Parameter< Eigen::VectorXd >, orca::common::Parameter< Eigen::Vector3d >, orca::common::Parameter< std::list< constraint::GenericConstraint::Ptr > >, orca::common::Parameter< robot::RobotModel::Ptr >, orca::common::Parameter< common::PIDController::Ptr >, and orca::common::Parameter< std::shared_ptr< T > >.
|
inline |
The callback called if loadFromString is successful.
|
pure virtual |
Implemented in orca::common::Parameter< std::list< T > >, orca::common::Parameter< T >, orca::common::Parameter< double >, orca::common::Parameter< Vector6d >, orca::common::Parameter< std::string >, orca::common::Parameter< int >, orca::common::Parameter< ResolutionStrategy >, orca::common::Parameter< math::Vector6d >, orca::common::Parameter< orca::common::PIDController::Ptr >, orca::common::Parameter< std::shared_ptr< common::CartesianServoController > >, orca::common::Parameter< std::list< task::GenericTask::Ptr > >, orca::common::Parameter< bool >, orca::common::Parameter< QPSolverImplType >, orca::common::Parameter< Eigen::VectorXd >, orca::common::Parameter< Eigen::Vector3d >, orca::common::Parameter< std::list< constraint::GenericConstraint::Ptr > >, orca::common::Parameter< robot::RobotModel::Ptr >, orca::common::Parameter< common::PIDController::Ptr >, and orca::common::Parameter< std::shared_ptr< T > >.
|
inline |
|
inline |