Joint velocity limit task map for non time-indexed problems. More...
#include <joint_velocity_limit_constraint.h>

| Public Member Functions | |
| void | AssignScene (ScenePtr scene) override | 
| void | SetPreviousJointState (Eigen::VectorXdRefConst joint_state) | 
| Logs current joint state. SetPreviousJointState must be called after solve is called in a Python/C++ script is called to ensure the time-derivative is appropriately approximated.  More... | |
| int | TaskSpaceDim () override | 
| void | Update (Eigen::VectorXdRefConst x, Eigen::VectorXdRef phi) override | 
| void | Update (Eigen::VectorXdRefConst x, Eigen::VectorXdRef phi, Eigen::MatrixXdRef jacobian) override | 
|  Public Member Functions inherited from exotica::TaskMap | |
| std::vector< KinematicFrameRequest > | GetFrames () const | 
| virtual std::vector< TaskVectorEntry > | GetLieGroupIndices () | 
| virtual void | InstantiateBase (const Initializer &init) | 
| virtual void | PreUpdate () | 
| virtual int | TaskSpaceJacobianDim () | 
| virtual void | Update (Eigen::VectorXdRefConst q, Eigen::VectorXdRef phi, Eigen::MatrixXdRef jacobian, HessianRef hessian) | 
| 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) | 
| 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) | 
|  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 | |
| virtual std::vector< Initializer > | GetAllTemplates () const=0 | 
| InstantiableBase ()=default | |
| virtual | ~InstantiableBase ()=default | 
|  Public Member Functions inherited from exotica::Instantiable< JointVelocityLimitConstraintInitializer > | |
| std::vector< Initializer > | GetAllTemplates () const override | 
| Initializer | GetInitializerTemplate () override | 
| const C & | GetParameters () const | 
| virtual void | Instantiate (const C &init) | 
| void | InstantiateInternal (const Initializer &init) override | 
| Private Attributes | |
| Eigen::VectorXd | current_joint_state_ | 
| Log of current joint state.  More... | |
| Eigen::MatrixXd | jacobian_ | 
| Task map jacobian matrix.  More... | |
| Eigen::VectorXd | joint_velocity_limits_ | 
| The joint velocity limits for the robot.  More... | |
| int | N_ | 
| Number of dofs for robot.  More... | |
| double | one_divided_by_dt_ | 
| Frequency (1/dt).  More... | |
| int | two_times_N_ | 
| Two multiplied by the number of dofs for robot (task space dimension).  More... | |
| Additional Inherited Members | |
|  Public Attributes inherited from exotica::TaskMap | |
| int | id | 
| bool | is_used | 
| std::vector< KinematicSolution > | kinematics | 
| 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< KinematicFrameRequest > | frames_ | 
| ScenePtr | scene_ | 
|  Protected Attributes inherited from exotica::Instantiable< JointVelocityLimitConstraintInitializer > | |
| C | parameters_ | 
Joint velocity limit task map for non time-indexed problems.
JointVelocityLimitConstraint constrains the joint velocity within a specified percentage of the velocity limit.
Definition at line 43 of file joint_velocity_limit_constraint.h.
| 
 | overridevirtual | 
Reimplemented from exotica::TaskMap.
Definition at line 36 of file joint_velocity_limit_constraint.cpp.
| void exotica::JointVelocityLimitConstraint::SetPreviousJointState | ( | Eigen::VectorXdRefConst | joint_state | ) | 
Logs current joint state. SetPreviousJointState must be called after solve is called in a Python/C++ script is called to ensure the time-derivative is appropriately approximated.
Definition at line 81 of file joint_velocity_limit_constraint.cpp.
| 
 | overridevirtual | 
Implements exotica::TaskMap.
Definition at line 112 of file joint_velocity_limit_constraint.cpp.
| 
 | overridevirtual | 
Implements exotica::TaskMap.
Definition at line 87 of file joint_velocity_limit_constraint.cpp.
| 
 | overridevirtual | 
Reimplemented from exotica::TaskMap.
Definition at line 101 of file joint_velocity_limit_constraint.cpp.
| 
 | private | 
Log of current joint state.
Definition at line 60 of file joint_velocity_limit_constraint.h.
| 
 | private | 
Task map jacobian matrix.
Definition at line 63 of file joint_velocity_limit_constraint.h.
| 
 | private | 
The joint velocity limits for the robot.
Definition at line 61 of file joint_velocity_limit_constraint.h.
| 
 | private | 
Number of dofs for robot.
Definition at line 58 of file joint_velocity_limit_constraint.h.
| 
 | private | 
Frequency (1/dt).
Definition at line 62 of file joint_velocity_limit_constraint.h.
| 
 | private | 
Two multiplied by the number of dofs for robot (task space dimension).
Definition at line 59 of file joint_velocity_limit_constraint.h.