Public Member Functions | Private Member Functions | Private Attributes | List of all members
exotica::JointVelocityLimit Class Reference

Joint Velocity Limit taskmap for time-indexed problems. Penalisations of joint velocity limit violation within a specified percentage of the velocity limit. More...

#include <joint_velocity_limit.h>

Inheritance diagram for exotica::JointVelocityLimit:
Inheritance graph
[legend]

Public Member Functions

void AssignScene (ScenePtr scene) override
 
 JointVelocityLimit ()
 
int TaskSpaceDim () override
 
void Update (Eigen::VectorXdRefConst x, Eigen::VectorXdRef phi) override
 
void Update (Eigen::VectorXdRefConst x, Eigen::VectorXdRef phi, Eigen::MatrixXdRef jacobian) override
 
virtual ~JointVelocityLimit ()
 
- Public Member Functions inherited from exotica::TaskMap
std::vector< KinematicFrameRequestGetFrames () const
 
virtual std::vector< TaskVectorEntryGetLieGroupIndices ()
 
virtual void InstantiateBase (const Initializer &init)
 
virtual void PreUpdate ()
 
virtual int TaskSpaceJacobianDim ()
 
virtual void Update (Eigen::VectorXdRefConst x, Eigen::VectorXdRefConst u, Eigen::VectorXdRef phi, Eigen::MatrixXdRef dphi_dx, Eigen::MatrixXdRef dphi_du)
 
virtual void Update (Eigen::VectorXdRefConst x, Eigen::VectorXdRefConst u, Eigen::VectorXdRef phi)
 
virtual void Update (Eigen::VectorXdRefConst x, Eigen::VectorXdRefConst u, Eigen::VectorXdRef phi, Eigen::MatrixXdRef dphi_dx, Eigen::MatrixXdRef dphi_du, HessianRef ddphi_ddx, HessianRef ddphi_ddu, HessianRef ddphi_dxdu)
 
virtual void Update (Eigen::VectorXdRefConst q, Eigen::VectorXdRef phi, Eigen::MatrixXdRef jacobian, HessianRef hessian)
 
- Public Member Functions inherited from exotica::Object
std::string GetObjectName ()
 
void InstantiateObject (const Initializer &init)
 
 Object ()
 
virtual std::string Print (const std::string &prepend) const
 
virtual std::string type () const
 
virtual ~Object ()
 
- Public Member Functions inherited from exotica::InstantiableBase
 InstantiableBase ()=default
 
virtual ~InstantiableBase ()=default
 
- Public Member Functions inherited from exotica::Instantiable< JointVelocityLimitInitializer >
std::vector< InitializerGetAllTemplates () const override
 
Initializer GetInitializerTemplate () override
 
const JointVelocityLimitInitializer & GetParameters () const
 
virtual void Instantiate (const JointVelocityLimitInitializer &init)
 
void InstantiateInternal (const Initializer &init) override
 

Private Member Functions

void Initialize ()
 

Private Attributes

double dt_ = 0.1
 Timestep between subsequent time-steps (in s) More...
 
Eigen::VectorXd limits_ = Eigen::VectorXd::Zero(1)
 Joint velocity limits (absolute, in rads/s) More...
 
int N
 
Eigen::VectorXd tau_ = Eigen::VectorXd::Zero(1)
 Joint velocity limits tolerance. More...
 

Additional Inherited Members

- Public Attributes inherited from exotica::TaskMap
int id
 
bool is_used
 
std::vector< KinematicSolutionkinematics
 
int length
 
int length_jacobian
 
int start
 
int start_jacobian
 
- Public Attributes inherited from exotica::Object
bool debug_
 
std::string ns_
 
std::string object_name_
 
- Protected Attributes inherited from exotica::TaskMap
std::vector< KinematicFrameRequestframes_
 
ScenePtr scene_
 
- Protected Attributes inherited from exotica::Instantiable< JointVelocityLimitInitializer >
JointVelocityLimitInitializer parameters_
 

Detailed Description

Joint Velocity Limit taskmap for time-indexed problems. Penalisations of joint velocity limit violation within a specified percentage of the velocity limit.

Definition at line 41 of file joint_velocity_limit.h.

Constructor & Destructor Documentation

exotica::JointVelocityLimit::JointVelocityLimit ( )

Definition at line 36 of file joint_velocity_limit.cpp.

exotica::JointVelocityLimit::~JointVelocityLimit ( )
virtualdefault

Member Function Documentation

void exotica::JointVelocityLimit::AssignScene ( ScenePtr  scene)
overridevirtual

Reimplemented from exotica::TaskMap.

Definition at line 43 of file joint_velocity_limit.cpp.

void exotica::JointVelocityLimit::Initialize ( )
private

Definition at line 49 of file joint_velocity_limit.cpp.

int exotica::JointVelocityLimit::TaskSpaceDim ( )
overridevirtual

Implements exotica::TaskMap.

Definition at line 77 of file joint_velocity_limit.cpp.

void exotica::JointVelocityLimit::Update ( Eigen::VectorXdRefConst  x,
Eigen::VectorXdRef  phi 
)
overridevirtual

Implements exotica::TaskMap.

Definition at line 82 of file joint_velocity_limit.cpp.

void exotica::JointVelocityLimit::Update ( Eigen::VectorXdRefConst  x,
Eigen::VectorXdRef  phi,
Eigen::MatrixXdRef  jacobian 
)
overridevirtual

Reimplemented from exotica::TaskMap.

Definition at line 105 of file joint_velocity_limit.cpp.

Member Data Documentation

double exotica::JointVelocityLimit::dt_ = 0.1
private

Timestep between subsequent time-steps (in s)

Definition at line 57 of file joint_velocity_limit.h.

Eigen::VectorXd exotica::JointVelocityLimit::limits_ = Eigen::VectorXd::Zero(1)
private

Joint velocity limits (absolute, in rads/s)

Definition at line 58 of file joint_velocity_limit.h.

int exotica::JointVelocityLimit::N
private

Definition at line 60 of file joint_velocity_limit.h.

Eigen::VectorXd exotica::JointVelocityLimit::tau_ = Eigen::VectorXd::Zero(1)
private

Joint velocity limits tolerance.

Definition at line 59 of file joint_velocity_limit.h.


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


exotica_core_task_maps
Author(s): Yiming Yang, Michael Camilleri
autogenerated on Sat Apr 10 2021 02:36:09