mc_rtc  2.14.0
mc_tvm::JointsSelectorFunction Class Reference

#include <mc_tvm/JointsSelectorFunction.h>

Inheritance diagram for mc_tvm::JointsSelectorFunction:
Collaboration diagram for mc_tvm::JointsSelectorFunction:

Public Types

using Function = tvm::function::abstract::Function
 
- Public Types inherited from tvm::graph::internal::AbstractNode
enum  Update_
 
typedef AbstractNode UpdateParent
 
typedef AbstractNode UpdateBase
 
- Public Types inherited from tvm::graph::internal::Inputs
typedef std::unordered_map< abstract::Outputs *, std::set< int > > inputs_t
 
typedef std::unordered_set< std::shared_ptr< abstract::Outputs > > store_t
 
- Public Types inherited from tvm::graph::abstract::Outputs
enum  Output_
 
typedef Outputs OutputParent
 
typedef Outputs OutputBase
 

Public Member Functions

const Eigen::VectorXd & value () const override
 
const Eigen::VectorXd & velocity () const override
 
const Eigen::VectorXd & normalAcceleration () const override
 
- Public Member Functions inherited from tvm::function::abstract::Function
virtual MatrixConstRef JDot (const Variable &x) const
 
- Public Member Functions inherited from tvm::internal::FirstOrderProvider
virtual MatrixConstRefWithProperties jacobian (const Variable &x) const
 
bool linearIn (const Variable &x) const
 
const SpaceimageSpace () const
 
int size () const
 
int rSize () const
 
int tSize () const
 
const VariableVectorvariables () const
 
- Public Member Functions inherited from tvm::graph::internal::AbstractNode
bool isUpdateEnabled (EnumT e) const
 
virtual bool isUpdateStaticallyEnabled (int) const
 
virtual bool isUpdateCustomEnabled (int) const
 
virtual ~AbstractNode ()=default
 
void update (int i)
 
- Public Member Functions inherited from tvm::graph::internal::Inputs
virtual ~Inputs ()=default
 
void addInput (std::shared_ptr< T > source, EnumI i, Args... args)
 
void addInput (T &source, EnumI i, Args... args)
 
void removeInput (T *source)
 
void removeInput (T *source, Args... args)
 
Iterator getInput (T *source)
 
Iterator getInput (const std::shared_ptr< T > &source)
 
- Public Member Functions inherited from tvm::graph::abstract::Outputs
virtual ~Outputs ()=default
 
bool isOutputEnabled (EnumT e) const
 
bool isOutputEnabled (int i) const
 
virtual bool isOutputStaticallyEnabled (int) const
 
virtual bool isOutputCustomEnabled (int) const
 

Static Public Member Functions

static std::unique_ptr< JointsSelectorFunctionActiveJoints (Function *f, const mc_rbdyn::Robot &robot, const std::vector< std::string > &activeJoints)
 
static std::unique_ptr< JointsSelectorFunctionInactiveJoints (Function *f, const mc_rbdyn::Robot &robot, const std::vector< std::string > &inactiveJoints)
 
- Static Public Member Functions inherited from tvm::graph::internal::AbstractNode
static constexpr const char * UpdateName (Update_)
 
static constexpr bool UpdateStaticallyEnabled (EnumT)
 
- Static Public Member Functions inherited from tvm::graph::abstract::Outputs
static constexpr const char * OutputName (Output_)
 
static constexpr bool OutputStaticallyEnabled (EnumT)
 

Protected Member Functions

 JointsSelectorFunction (Function *f, tvm::VariablePtr variable, const std::vector< std::pair< Eigen::DenseIndex, Eigen::DenseIndex >> &activeIndex)
 
void updateJacobian ()
 
void updateJDot ()
 
- Protected Member Functions inherited from tvm::function::abstract::Function
 Function (int m=0)
 
 Function (Space image)
 
void resizeCache () override
 
void resizeVelocityCache ()
 
void resizeNormalAccelerationCache ()
 
void resizeJDotCache ()
 
void addVariable_ (VariablePtr v) override
 
void removeVariable_ (VariablePtr v) override
 
- Protected Member Functions inherited from tvm::internal::FirstOrderProvider
 FirstOrderProvider (int m)
 
 FirstOrderProvider (Space image)
 
void resizeValueCache ()
 
void resizeJacobianCache ()
 
void addVariable (VariablePtr v, bool linear)
 
void removeVariable (VariablePtr v)
 
void addVariable (const VariableVector &v, bool linear)
 
void splitJacobian (const MatrixConstRef &J, const std::vector< VariablePtr > &vars, bool keepProperties=false)
 
void splitJacobian (const MatrixConstRef &J, const VariableVector &vars, bool keepProperties=false)
 
void resize (int m)
 
- Protected Member Functions inherited from Node< FirstOrderProvider >
void registerUpdates (EnumT u, void(U::*fn)(), Args... args)
 
void registerUpdates (EnumT u, void(U::*fn)())
 
void addOutputDependency (EnumO o, EnumU u)
 
void addOutputDependency (std::initializer_list< EnumO > os, EnumU u)
 
void addInternalDependency (EnumU1 uDependent, EnumU2 u)
 
void addInputDependency (EnumU u, std::shared_ptr< S > source, EnumO i, Args... args)
 
void addInputDependency (EnumU u, S &source, EnumO i, Args... args)
 
void addDirectDependency (EnumO o, std::shared_ptr< S > source, EnumI i)
 
void addDirectDependency (EnumO o, S &source, EnumI i)
 

Protected Attributes

Functionf_
 
tvm::VariablePtr variable_
 
std::vector< std::pair< Eigen::DenseIndex, Eigen::DenseIndex > > activeIndex_
 
- Protected Attributes inherited from tvm::function::abstract::Function
Eigen::VectorXd velocity_
 
Eigen::VectorXd normalAcceleration_
 
utils::internal::MapWithVariableAsKey< Eigen::MatrixXd, slice_jdotJDot_
 
- Protected Attributes inherited from tvm::internal::FirstOrderProvider
Eigen::VectorXd value_
 
utils::internal::MapWithVariableAsKey< MatrixWithProperties, slice_matrix, true > jacobian_
 
Space imageSpace_
 
VariableVector variables_
 
utils::internal::MapWithVariableAsKey< bool, slice_linearlinear_
 
- Protected Attributes inherited from tvm::graph::internal::AbstractNode
std::map< int, std::function< void(AbstractNode &)> > updates_
 
std::map< int, std::vector< int > > outputDependencies_
 
std::map< int, std::vector< int > > internalDependencies_
 
std::map< int, input_dependency_tinputDependencies_
 
std::map< int, std::pair< Outputs *, int > > directDependencies_
 
- Protected Attributes inherited from tvm::graph::abstract::Outputs
bool is_node_
 

Additional Inherited Members

- Static Public Attributes inherited from tvm::graph::internal::AbstractNode
static constexpr unsigned int UpdateSize
 
static constexpr auto UpdateBaseName
 
- Static Public Attributes inherited from tvm::graph::abstract::Outputs
static constexpr unsigned int OutputSize
 
static constexpr auto OutputBaseName
 
- Protected Types inherited from tvm::graph::internal::AbstractNode
typedef std::map< Outputs *, std::set< int > > input_dependency_t
 

Detailed Description

This class implements joints' selection on a given fucntion

Member Typedef Documentation

◆ Function

Constructor & Destructor Documentation

◆ JointsSelectorFunction()

mc_tvm::JointsSelectorFunction::JointsSelectorFunction ( Function f,
tvm::VariablePtr  variable,
const std::vector< std::pair< Eigen::DenseIndex, Eigen::DenseIndex >> &  activeIndex 
)
protected

Constructor

Parameters
fFunction selected by this JointsSelector
robotRobot controlled by f
fbActiveTrue if the selected joints include the floating-base
activeIndexFor regular joints selected by this JointsSelector, this iss a list of (start, size) pair corresponding to the list of joints

Member Function Documentation

◆ ActiveJoints()

static std::unique_ptr<JointsSelectorFunction> mc_tvm::JointsSelectorFunction::ActiveJoints ( Function f,
const mc_rbdyn::Robot robot,
const std::vector< std::string > &  activeJoints 
)
static

Construct a JointsSelector from a vector of active joints

Parameters
fFunction selected by this JointsSelector
robotRobot controlled by f
activeJointsJoints active in this selector
Exceptions
Ifdoes not depend on robot or any joint in activeJoints is not part of robot

◆ InactiveJoints()

static std::unique_ptr<JointsSelectorFunction> mc_tvm::JointsSelectorFunction::InactiveJoints ( Function f,
const mc_rbdyn::Robot robot,
const std::vector< std::string > &  inactiveJoints 
)
static

Construct a JointsSelector from a vector of inactive joints

Parameters
fFunction selected by this JointsSelector
robotRobot controlled by f
inactiveJointsJoints not active in this selector
Exceptions
Ifdoes not depend on robot or any joint in activeJoints is not part of robot

◆ normalAcceleration()

const Eigen::VectorXd& mc_tvm::JointsSelectorFunction::normalAcceleration ( ) const
inlineoverridevirtual

Reimplemented from tvm::function::abstract::Function.

◆ updateJacobian()

void mc_tvm::JointsSelectorFunction::updateJacobian ( )
protected

◆ updateJDot()

void mc_tvm::JointsSelectorFunction::updateJDot ( )
protected

◆ value()

const Eigen::VectorXd& mc_tvm::JointsSelectorFunction::value ( ) const
inlineoverridevirtual

Reimplemented from tvm::internal::FirstOrderProvider.

◆ velocity()

const Eigen::VectorXd& mc_tvm::JointsSelectorFunction::velocity ( ) const
inlineoverridevirtual

Reimplemented from tvm::function::abstract::Function.

Member Data Documentation

◆ activeIndex_

std::vector<std::pair<Eigen::DenseIndex, Eigen::DenseIndex> > mc_tvm::JointsSelectorFunction::activeIndex_
protected

◆ f_

Function* mc_tvm::JointsSelectorFunction::f_
protected

◆ variable_

tvm::VariablePtr mc_tvm::JointsSelectorFunction::variable_
protected

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