BipedalLocomotion::Estimators::RobotDynamicsEstimator::SubModel class

SubModel is a concrete class describing the sub-model object, its model, the list of sensors and the mapping between its joints and the same joints in the full model.

Public functions

auto isValid() const -> bool
Determines the validity of the object.
auto getModel() const -> const iDynTree::Model&
Getters.
auto getJointMapping() const -> const std::vector<int>&
Access the std::vectot<int> list.
auto getFTList() const -> const std::unordered_map<std::string, FT>&
Access the std::vector<FT> list.
auto getAccelerometerList() const -> const std::unordered_map<std::string, Sensor>&
Access the std::vector<Sensor> list of acceletometer sensors.
auto getGyroscopeList() const -> const std::unordered_map<std::string, Sensor>&
Access the std::vector<Sensor> list of gyroscope sensors.
auto getExternalContactList() const -> const std::unordered_map<std::string, int>&
Access the std::vector<std::string> list of frame names.
auto getNrOfFTSensor() const -> std::size_t
access the length of force/torque sensor list.
auto getNrOfAccelerometer() const -> std::size_t
access the length of accelerometer list.
auto getNrOfGyroscope() const -> std::size_t
access the length of gyroscope list.
auto getNrOfExternalContact() const -> std::size_t
access the length of the contact frame list.
auto getFTSensor(const std::string& name) -> const FT&
Access an element of the force/torque sensor list.
auto hasFTSensor(const std::string& name) const -> bool
hasFTSensor check if the force/torque sensor is part of the sub-model
auto getAccelerometer(const std::string& name) -> const Sensor&
Access an element of the accelerometer list.
auto hasAccelerometer(const std::string& name) const -> bool
hasAccelerometer check if the accelerometer is part of the sub-model
auto getGyroscope(const std::string& name) -> const Sensor&
Access an element of the gyroscope list.
auto hasGyroscope(const std::string& name) const -> bool
hasAccelerometer check if the gyroscope is part of the sub-model
auto getExternalContactIndex(const std::string& name) -> int
access an element of the contact frame list.

Function documentation

bool BipedalLocomotion::Estimators::RobotDynamicsEstimator::SubModel::isValid() const

Determines the validity of the object.

Returns True if the object is valid, false otherwise.

const iDynTree::Model& BipedalLocomotion::Estimators::RobotDynamicsEstimator::SubModel::getModel() const

Getters.

Returns The model of the SubModel.

Get the iDynTree::Model instance.

const std::vector<int>& BipedalLocomotion::Estimators::RobotDynamicsEstimator::SubModel::getJointMapping() const

Access the std::vectot<int> list.

Returns the mapping between the joint indeces in the sub-model and the joint indeces in the full-model.

const std::unordered_map<std::string, FT>& BipedalLocomotion::Estimators::RobotDynamicsEstimator::SubModel::getFTList() const

Access the std::vector<FT> list.

Returns a map of (string, FT) objects which is the list of force/torque sensors.

const std::unordered_map<std::string, Sensor>& BipedalLocomotion::Estimators::RobotDynamicsEstimator::SubModel::getAccelerometerList() const

Access the std::vector<Sensor> list of acceletometer sensors.

Returns a map of (string, Sensor) objects describing the accelerometers contained in the sub-model.

const std::unordered_map<std::string, Sensor>& BipedalLocomotion::Estimators::RobotDynamicsEstimator::SubModel::getGyroscopeList() const

Access the std::vector<Sensor> list of gyroscope sensors.

Returns a map of (string, Sensor) objects describing the gyroscope contained in the sub-model.

const std::unordered_map<std::string, int>& BipedalLocomotion::Estimators::RobotDynamicsEstimator::SubModel::getExternalContactList() const

Access the std::vector<std::string> list of frame names.

Returns a list of strings describing frame names of the external contacts for the sub-model.

std::size_t BipedalLocomotion::Estimators::RobotDynamicsEstimator::SubModel::getNrOfFTSensor() const

access the length of force/torque sensor list.

Returns the number of force/torque sensors in the sub-model.

std::size_t BipedalLocomotion::Estimators::RobotDynamicsEstimator::SubModel::getNrOfAccelerometer() const

access the length of accelerometer list.

Returns the number of accelerometer sensors in the sub-model.

std::size_t BipedalLocomotion::Estimators::RobotDynamicsEstimator::SubModel::getNrOfGyroscope() const

access the length of gyroscope list.

Returns the number of gyroscope sensors in the sub-model.

std::size_t BipedalLocomotion::Estimators::RobotDynamicsEstimator::SubModel::getNrOfExternalContact() const

access the length of the contact frame list.

Returns the number of gyroscope sensors in the sub-model.

const FT& BipedalLocomotion::Estimators::RobotDynamicsEstimator::SubModel::getFTSensor(const std::string& name)

Access an element of the force/torque sensor list.

Returns FT object associated with the specified name.

bool BipedalLocomotion::Estimators::RobotDynamicsEstimator::SubModel::hasFTSensor(const std::string& name) const

hasFTSensor check if the force/torque sensor is part of the sub-model

Parameters
name is the name of the ft sensor
Returns true if the sensor is found, false otherwise

const Sensor& BipedalLocomotion::Estimators::RobotDynamicsEstimator::SubModel::getAccelerometer(const std::string& name)

Access an element of the accelerometer list.

Returns a Sensor object corresponding to the accelerometer associated with the specified name.

bool BipedalLocomotion::Estimators::RobotDynamicsEstimator::SubModel::hasAccelerometer(const std::string& name) const

hasAccelerometer check if the accelerometer is part of the sub-model

Parameters
name is the name of the accelerometer
Returns true if the sensor is found, false otherwise

const Sensor& BipedalLocomotion::Estimators::RobotDynamicsEstimator::SubModel::getGyroscope(const std::string& name)

Access an element of the gyroscope list.

Returns a Sensor object corresponding to the gyroscope associated with the specified name.

bool BipedalLocomotion::Estimators::RobotDynamicsEstimator::SubModel::hasGyroscope(const std::string& name) const

hasAccelerometer check if the gyroscope is part of the sub-model

Parameters
name is the name of the gyroscope
Returns true if the sensor is found, false otherwise

int BipedalLocomotion::Estimators::RobotDynamicsEstimator::SubModel::getExternalContactIndex(const std::string& name)

access an element of the contact frame list.

Returns a string corresponding to the external contact frame associated with the specified index.