Classes
- namespace bfl
-
namespace BipedalLocomotion
-
namespace AutoDiff
- namespace CppAD
-
namespace ContactModels
- class ContactModel ContactModel is a generic implementation of a contact model.
- class ContinuousContactModel final ContinuousContactModel is a model that describe the contact using a continuous representation.
-
namespace Contacts
- struct ContactBase Definition of the type of contact base class.
- class ContactDetector
-
class ContactList Class containing a list of contacts.
- struct ContactCompare Struct used for inserting new contacts in the set.
- struct ContactPhase Struct defining a contact phase.
- class ContactPhaseList The ContactPhaseList class computes the contact phases according to a bunch of input contact lists.
- struct ContactWrench Definition of an ContactWrench structure.
- struct Corner Definition of a corner.
- struct DiscreteGeometryContact DiscreteGeometryContact is a contact which is represented by a set of corners that exchanges a pure force whith the enviroment.
- struct EstimatedContact Definition of an Estimated Contact structure.
- class FixedFootDetector The FixedFootDetector is a class that can be used to find the fixed foot given a sequence of contacts.
- class GlobalCoPEvaluator GlobalCoPEvaluator is a class that computes the global CoP given a set of contact wrenches.
- struct PlannedContact Definition of a Planned Contact structure.
- class SchmittTriggerDetector Schmitt Trigger thresholding based contact detector that maintains and updates the contact states for a prescribed set of contacts.
-
namespace ContinuousDynamicalSystem
- namespace internal
- class ButterworthLowPassFilter ButterworthLowPass implements a low pass filter of order N.
- class CentroidalDynamics CentroidalDynamics describes the centroidal dynamics of a multi-body system.
- class CompliantContactWrench A wrench excerted on a link due to an external contact.
- class DynamicalSystem DynamicalSystem defines a continuous time dynamical system, i.e.
- class FirstOrderSmoother FirstOrderSmoother smoother implements a simple smoother based on a first order linear system.
- class FixedBaseDynamics FixedBaseDynamics describes a the dynamics of a fixed base system The FixedBaseDynamics inherits from a generic DynamicalSystem where the State is described by a BipedalLocomotion::
GenericContainer:: named_tuple. - class FixedStepIntegrator Fixed step integrator base class.
- class FloatingBaseDynamicsWithCompliantContacts FloatingBaseDynamicalSystem describes a floating base dynamical system.
- class FloatingBaseSystemKinematics FloatingBaseSystemKinematics describes a floating base system kinematics.
- class ForwardEuler Forward Euler integration method.
- class Integrator Integrator base class.
- class LieGroupDynamics LieGroupDynamics describes the dynamics of a LieGroup.
- class LinearTimeInvariantSystem LinearTimeInvariantSystem describes a MIMO linear time invariant system of the form where x is the state and u the control input.
- class MultiStateWeightProvider MultiStateWeightProvider describes the provider for a constant weight.
- class RK4 RK4 implements the runge-kutta 4 integration method.
- namespace Conversions
-
namespace Estimators
-
namespace FloatingBaseEstimators
- struct InternalState Struct holding the elements of the state representation.
- struct Measurements Struct holding the elements of the measurements data.
- struct Options Struct containing options runtime options for floating base estimator.
- struct Output Struct holding the elements of the estimator output.
- struct SensorsStdDev Struct containing sensor measurement deviation parameters of floating base estimators.
- struct StateStdDev Struct containing prior state deviation parameters of floating base estimators.
-
namespace RobotDynamicsEstimator
- class AccelerometerMeasurementDynamics The AccelerometerMeasurementDynamics class is a concrete implementation of the Dynamics.
- class ConstantMeasurementModel The ConstantMeasurementModel class is a concrete implementation of the Dynamics.
- class Dynamics The class Dynamics represents a base class describing a generic model composing the ukf process model or the ukf measurement model.
- class DynamicsFactory DynamicsFactory implements the factory design patter for constructing a Dynamics given its model.
- class ExternalContactStateDynamics The ExternalContactStateDynamics class is a concrete implementation of the Dynamics.
- class FrictionTorqueStateDynamics The FrictionTorqueDynamics class is a concrete implementation of the Dynamics.
- struct FTSensor FTSensor describes the force/torque sensors of the submodels.
- class GyroscopeMeasurementDynamics The GyroscopeMeasurementDynamics class is a concrete implementation of the Dynamics.
- class JointVelocityStateDynamics The JointVelocityDynamics class is a concrete implementation of the Dynamics.
- class KinDynWrapper KinDynWrapper is a concrete class and implements a wrapper of the KinDynComputation class from iDynTree.
- class MotorCurrentMeasurementDynamics The MotorCurrentMeasurementDynamics class is a concrete implementation of the Dynamics.
- class RobotDynamicsEstimator RobotDynamicsEstimator is a concrete class and implements a robot dynamics estimator.
- struct RobotDynamicsEstimatorInput RobotDynamicsEstimatorInput of the RobotDynamicsEstimator containing both the inputs and the measurements for the Unscented Kalman Filter.
- struct RobotDynamicsEstimatorOutput RobotDynamicsEstimatorOutput of the RobotDynamicsEstimator which represents the estimation of the Unscented Kalman Filter.
- struct Sensor Sensor describes the generic sensors of the submodels.
- class SubModel 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.
- class SubModelCreator SubModelCreator is a concrete class and splits a model into sub-models along the force/torque sensors specified as configuration parameters.
- struct UKFInput The UKFInput struct represents the input of the ukf needed to update the dynamics.
- class UkfInputProvider UkfInputProvider describes the provider for the inputs of the ukf.
- class UkfMeasurement UkfMeasurement is a concrete class that represents the Measurement of the estimator.
- class UkfModel UkfModel is a base class to define the process and measurement model of the UKF.
- class UkfState UkfState is a concrete class that represents the State of the estimator.
- class ZeroVelocityStateDynamics The ZeroVelocityStateDynamics class is a concrete implementation of the Dynamics.
- class BaseEstimatorFromFootIMU BaseEstimatorFromFootIMU implements the propagation of the foot pose to the root link through the kinematic chain given by the leg joints positions.
- struct BaseEstimatorFromFootIMUInput BaseEstimatorFromFootIMUInput contains the input of the BaseEstimatorFromFootIMU class.
- struct BaseEstimatorFromFootIMUState BaseEstimatorFromFootIMUState contains the internal state of the estimator.
-
class FloatingBaseEstimator FloatingBaseEstimator class contains the bare-bones implementation for a LeggedOdometry based or Extended Kalman Filter based floating base estimation algorithms for bipedal robots.
- class ModelComputations iDynTree based model-specific computations class This is class is used in a required configuration step for the estimator All the model related kinematics and dynamics computations specific to the floating base estimator are contained within this class.
- class InvariantEKFBaseEstimator InvariantEKFBaseEstimator class implements the Contact Aided Invariant EKF algorithm, developed by Ross Hartley, Maani Ghaffari, Ryan M.
- class LeggedOdometry Floating base estimation algorithm using only kinematic measurements by assuming atleast one frame on the robot is in contact with the environment.
- class RecursiveLeastSquare
- struct RecursiveLeastSquareState RecursiveLeastSquare contains the implementation of the Recursive least square filter described in Lennart Ljung - System Identification Theory for the User (1999, Prentice Hall).
-
namespace FloatingBaseEstimators
-
namespace GenericContainer
- namespace detail
- namespace literals
- struct is_span_constructible is_
span_ constructible is a utility metafunction to check if iDynTree::Span is constructible given a reference to Class. - struct is_span_constructible<Class, typename std::enable_if<std::is_constructible<iDynTree::Span<typename container_data<Class>::type>, Class&>::value>::type> is_
span_ constructible is a utility metafunction to check if iDynTree::Span is constructible given a reference to Class. - struct is_vector is_
vector is a utility metafunction used to check if T is a GenericContainer:: Vector. - struct is_vector<Vector<T>> is_
vector is a utility metafunction used to check if T is a GenericContainer:: Vector. - struct is_vector_constructible is_
vector_ constructible is a utility metafunction to check if GenericContainer:: Vector is constructible given a type T. - struct named_param named_
param is a struct that associate a compile time hash to a value. - struct named_tuple named_
tuple is a class that inherits from tuple. - class Vector Forward declaration of Vector class.
-
namespace IK
- class AngularMomentumTask AngularMomentumTask is a concrete implementation of the Task.
- class CoMTask SE3Task is a concrete implementation of the Task.
- class DistanceTask The DistanceTask class controls the distance of a frame with respect the world origin, or another frame.
- class GravityTask The GravityTask class aligns the z axis of a frame to a desired gravity direction.
- struct IKLinearTask IKLinearTask specializes a LinearTask in the case of Inverse Kinematics.
- class IntegrationBasedIK IntegrationBasedIK implements the interface for the integration base inverse kinematics.
- struct IntegrationBasedIKProblem IntegrationBasedIKProblem store all the ingredients to run an modfy at runtime an Integration based inverse kinematics problem.
- struct IntegrationBasedIKState State of the IntegrationBasedIK.
- class JointLimitsTask JointLimitsTask is a concrete implementation of the Task.
- class JointTrackingTask JointsTrackingTask is a concrete implementation of the Task.
- class JointVelocityLimitsTask JointVelocityLimitsTask is a concrete implementation of the Task.
- class QPFixedBaseInverseKinematics QPFixedBaseInverseKinematics is specialization of QPInverseKinematics class in the case of fixed base system.
- class QPInverseKinematics QPInverseKinematics is a concrete class and implements an integration base inverse kinematics.
- class R3Task R3Task is a concrete implementation of the Task.
- class SE3Task SE3Task is a concrete implementation of the Task.
- class SO3Task SO3Task is a concrete implementation of the IK::Task.
-
namespace Math
- class CARE Computes the unique stabilizing solution S to the continuous-time algebraic equation.
- class ContactWrenchCone ContactWrenchCone computes the polyhedral approximation of the contact wrench friction cone.
- class CubicSpline Cubic spline implements a 3-rd order polynomial spline in .
- class LinearizedFrictionCone LinearizedFrictionCone computes the polyhedral approximation of the friction cone.
- class LinearSpline LinearSpline implements a 1-st order polynomial spline in .
- class QuadraticBezierCurve QuadraticBezierCurve implements a quadratic Bézier curve.
- class QuinticSpline Quintic spline implements a 5-th order polynomial spline in .
-
class SchmittTrigger SchmittTrigger implements a discrete version of a SchmittTrigger See here for further details.
- struct Params Struct holding switching parameters for the Schmitt Trigger.
- struct SchmittTriggerInput SchmittTriggerState contains the input of the SchmittTrigger class.
- struct SchmittTriggerOutput
- struct SchmittTriggerState SchmittTriggerState contains the internal state of the trigger,.
-
class Spline Spline implement a basic spline.
- struct DerivativeBoundaryConditions BoundaryConditions is a struct that contains the boundary conditions of the spline.
- struct Polynomial Polynomial is a struct that contains the information of a polynomial.
- struct TrajectoryPoint TrajectoryPoint is a struct that contains the information of a trajectory point.
- class Wrench Wrench represent a wrench, i.e.
- class ZeroOrderSpline ZeroOrderSpline implements a 0 order polynomial spline in .
-
namespace ML
- class MANN MANN is a class that allows to perform the inference of an
onnx
implementing Mode-Adaptive Neural Networks (MANN). -
class MANNAutoregressive MANNAutoregressive is a class that allows to perform autoregressive inference with Mode-Adaptive Neural Networks (MANN).
- struct AutoregressiveState AutoregressiveState contains all quantities required to reset the Advanceable The base position trajectory, facing direction trajectory and base velocity trajectories are written in a bidimensional local reference frame L in which we assume all the quantities related to the ground-projected base trajectory in xi and yi to be expressed.
- struct MANNAutoregressiveInput MANNAutoregressiveInput contains the unput to MANN network when used in autoregressive fashion.
- class MANNAutoregressiveInputBuilder MANNAutoregressiveInputBuilder generates a MANNAutoregressiveInput from a pair of directional inputs.
- struct MANNAutoregressiveOutput MANNAutoregressiveOutput contains the output to the MANN network when used in autoregressive fashion.
- struct MANNDirectionalInput Structure representing directional input for MANNAutoregressive.
- struct MANNFootState MANNFootState contains the state of a foot in contact with the ground.
- struct MANNInput MANNInput contains the input to the MANN network.
- struct MANNOutput MANNOutput contains the output to the MANN network.
- class MANNTrajectoryGenerator MANNTrajectoryGenerator is a class that uses MANNAutoregressive to generate a kinematically feasible trajectory for humanoid robots.
- struct MANNTrajectoryGeneratorInput Input of the planner.
- struct MANNTrajectoryGeneratorOutput Output of the trajectory planner.
- class MANN MANN is a class that allows to perform the inference of an
-
namespace ParametersHandler
- class IParametersHandler Parameters handler interface.
- class StdImplementation Parameters handler interface.
- class TomlImplementation TomlImplementation Toml implementation of the IParametersHandler interface.
- class YarpImplementation YarpImplementation Yarp implementation of the IParametersHandler interface.
-
namespace Perception
-
namespace Capture
- class RealSense Realsense driver class.
-
namespace Features
- struct PCLProcessorParameters
- class PointCloudProcessor A wrapper class to do a basic PCL processing for perception aided locomotion.
- class ArucoDetector
- struct ArucoDetectorOutput Aruco detector output.
- struct ArucoMarkerData Aruco marker identifiers.
-
namespace Capture
-
namespace Planners
-
namespace UnicycleUtilities
- namespace Conversions
- class ConvexHullHelper ConvexHullHelper is an helper class that simplifies the building of a convex hull given a set of points that belongs to .
- class DCMPlanner DCMPlanner defines a trajectory generator for the variable height Divergent component of motion (DCM).
- struct DCMPlannerState DCMPlannerState describes the state of the Divergent Component of Motion (DCM) planner.
-
class SO3Planner SO3Planner implements a minimum jerk trajectory planner for object belonging to SO(3).
- struct BoundaryConditions Struct containing the boundary condition.
- struct Polynomial Description of a 5-th polynomial.
- struct SO3PlannerState SO3PlannerState contains the state of the planner.
- class SwingFootPlanner SwingFootPlanner implement a minimum jerk trajectory planner for the swing foot.
- struct SwingFootPlannerState SwingFootPlannerState describes the state of Swing foot planner.
- class TimeVaryingDCMPlanner DCMPlanner defines a trajectory generator for the variable height Divergent component of motion (DCM).
- class UnicycleTrajectoryGenerator final UnicycleTrajectoryGenerator is a class that generates reference trajectories for humanoid robots.
- struct UnicycleTrajectoryGeneratorInput
- struct UnicycleTrajectoryGeneratorOutput
- struct UnicycleTrajectoryGeneratorParameters
- class UnicycleTrajectoryPlanner final UnicycleTrajectoryPlanner is a class that uses UnicycleGenerator of https:/
/ github.com/ robotology/ unicycle-footstep-planner) to generate reference trajectories for humanoid robots. -
struct UnicycleTrajectoryPlannerInput
- struct COMInitialState
-
struct UnicycleTrajectoryPlannerOutput
- struct COMTrajectory
- struct ContactStatus
- struct DCMTrajectory
- struct FootTrajectory
- struct Steps
- struct UnicycleTrajectoryPlannerParameters
-
namespace UnicycleUtilities
-
namespace ReducedModelControllers
- class CentroidalMPC CentroidalMPC implements a Non-Linear Model Predictive Controller for humanoid robot locomotion with online step adjustment capabilities.
- struct CentroidalMPCOutput CentroidalMPCOutput contains the output of the CentroidalMPC class.
-
namespace RobotInterface
- struct CameraBridgeMetaData Meta data struct to hold list of sensors and configured options available from the Sensor bridge interface.
- struct CameraBridgeOptions Camera bridge options.
- struct CameraLists Camera lists.
- class ICameraBridge Sensor bridge interface.
- class IPointCloudBridge Sensor bridge interface.
- class IRobotControl Robot control interface.
- class ISensorBridge Sensor bridge interface.
- struct PCLBridgeMetaData Meta data struct to hold list of sensors and configured options available from the Sensor bridge interface.
- struct PCLDeviceLists Device lists.
- struct PolyDriverDescriptor PolyDriverDescriptor describes a PolyDriver.
- struct SensorBridgeMetaData Meta data struct to hold list of sensors and configured options available from the Sensor bridge interface.
- struct SensorBridgeOptions Sensor bridge options.
- struct SensorLists Sensor lists.
- class YarpCameraBridge YarpCameraBridge Yarp implementation of the ICameraBridge interface Currently available interfaces.
- class YarpRobotControl YarpRobotControl Yarp implementation of the IRobotControl interface.
-
class YarpSensorBridge YarpSensorBridge Yarp implementation of the ISensorBridge interface Currently available interfaces.
-
struct Impl
- struct ControlBoardRemapperInterfaces Struct holding remapped remote control board interfaces.
- struct ControlBoardRemapperMeasures Struct holding measurements polled from remapped remote control board interfaces.
- struct MASForceTorquesInterface Struct holding remapped MAS interfaces - FT sensors related.
- struct MASInertialsInterface Struct holding remapped MAS interfaces -inertial sensors related.
- struct MASSensorIndexMaps
-
struct Impl
-
namespace SimplifiedModelControllers
- class CoMZMPController CoMZMPController implements the following control law.
- struct CoMZMPControllerInput
-
namespace System
- class Advanceable Basic class that represents a discrete system.
-
class AdvanceableRunner AdvanceableRunner is an helper class that can be used to run a advanceable at a given period.
- struct Info
- class Barrier Barrier provides a thread-coordination mechanism that allows an expected number of threads to block until the expected number of threads arrive at the barrier.
- class ClockBuilder
- class ClockFactory ClockFactory is an interface that implements the factory paradigm.
- class ConstantWeightProvider ConstantWeightProvider describes the provider for a constant weight.
- class Factory Factory implements the factory design patter for constructing a an object of a given Type given its id.
- class IClock IClock is the interface to the clock.
- class ILinearTaskFactory ILinearTaskFactory implements the factory design patter for constructing a linear task given its type.
- class ILinearTaskSolver ILinearTaskSolver describes the interface for solving problem related to LinearTask class.
- class InputPort Basic class that represents an input port.
- struct ITaskControllerManager ITaskControllerManager is an interface that can help you to handle tasks containing controllers.
- class LinearTask LinearTask describes a Linear Task element.
- class OutputPort Basic class that represents an output port.
- class RosClock final RosClock implements the IClock interface using ros functions.
- class RosClockFactory final
- class SharedResource Basic class that contains a shared resource between two Block classes.
- class Sink Sink is a template specialization of Advanceable and represents a block that does not contains output.
- class Source Source is a template specialization of Advanceable and represents a block that does not contains input.
- class StdClock final StdClock implements the IClock interface using
<chrono>
from c++std library. - class StdClockFactory final
- class TimeProfiler TimeProfiler is a simple class that can be used to profile the code.
- class Timer Timer is a simple class that can be used to measure the time between two events.
-
class VariablesHandler VariableHandler is useful to handle variables in an optimization problem, Their name, dimension and position.
- class VariableDescription
- struct WeightProvider WeightProvider describes the provider for a weight.
- class WeightProviderFactory WeightProviderFactory implements the factory design patter for constructing a WeightProvidergiven its type.
- class YarpClock final YarpClock implements the IClock interface using yarp functions.
- class YarpClockFactory final
-
namespace TestUtils
- class MemoryAllocationMonitor
-
namespace TextLogging
- namespace sinks
- class DefaultLoggerFactory final
- class LoggerBuilder LoggerBuilder is a class that implements the Builder paradigm.
- class LoggerFactory LoggerFactory is an interface that implements the factory paradigm.
- class RosLoggerFactory final RosLoggerFactory implements the factory you should use to enable the sink using ros.
- class YarpLoggerFactory final YarpLoggerFactory implements the factory you should use to enable the sink using yaro.
-
namespace TSID
-
class AngularMomentumTask AngularMomentumTask is a concrete implementation of the TSIDLinearTask.
- struct ContactWrench
-
class BaseDynamicsTask BaseDynamicsTask is a concrete implementation of the Task.
- struct ContactWrench
- class CoMTask ComTask is a concrete implementation of the TSIDLinearTask.
-
class FeasibleContactWrenchTask FeasibleContactWrenchTask is a concrete implementation of the TSIDLinearTask.
- struct ContactWrench
-
class JointDynamicsTask JointsDynamicsTask is a concrete implementation of the Task.
- struct ContactWrench
- class JointTrackingTask JointsTrackingTask is a concrete implementation of the Task.
- class QPFixedBaseTSID QPFixedBaseTSID is specialization of QPTSID class in the case of fixed base system.
- class QPTSID QPTSID is a concrete class and implements a task space inverse dynamics.
- class R3Task SE3Task is a concrete implementation of the OptimalControlElement.
- class SE3Task SE3Task is a concrete implementation of the OptimalControlElement.
- class SO3Task SO3Task is a concrete implementation of the TSIDLinearTask.
- class TaskSpaceInverseDynamics TaskSpaceInverseDynamics implements the interface for the task space inverse dynamics.
- struct TaskSpaceInverseDynamicsProblem TaskSpaceInverseDynamicsProblem store all the ingredients to run an modify at runtime an TaskSpaceInverseDynamics problem.
- struct TSIDLinearTask TSIDLinearTask specializes a LinearTask in the case of Task based Inverse Dynamics.
- struct TSIDState State of the TaskSpaceInverseDynamics.
- class VariableRegularizationTask VariableRegularizationTask is a concrete implementation of the Task.
-
class AngularMomentumTask AngularMomentumTask is a concrete implementation of the TSIDLinearTask.
-
namespace YarpUtilities Helper for YARP library.
- class RosPublisher The class internally contains a YARP based ROS node and a set of publishers.
- class VectorsCollectionClient VectorsCollectionClient is a class that implements that allows to receive a VectorsCollection from a VectorsCollectionServer.
- class VectorsCollectionServer VectorsCollectionServer is a class that implements the VectorsCollectionMetadataService.
-
namespace AutoDiff
-
namespace Eigen
-
namespace internal
- struct cast_impl<CppAD::AD<Scalar>, Scalar> cast_impl
-
namespace internal
- namespace iDynTree
-
namespace spdlog
- namespace sinks
-
namespace std STL namespace.
- struct tuple_element<Index, ::BipedalLocomotion::GenericContainer::named_tuple<Params...>> Template specialization to make the elements of the named_tuple accessible with the Structured binding declaration.
- struct tuple_element<Index, ::BipedalLocomotion::IK::IntegrationBasedIKProblem>
- struct tuple_element<Index, ::BipedalLocomotion::TSID::TaskSpaceInverseDynamics>
- struct tuple_size<::BipedalLocomotion::GenericContainer::named_tuple<Params...>> Template specialization to make the elements of the named_tuple accessible with the Structured binding declaration.
- struct tuple_size<::BipedalLocomotion::IK::IntegrationBasedIKProblem>
- struct tuple_size<::BipedalLocomotion::TSID::TaskSpaceInverseDynamics>