Time-derivative estimation by backward differencing. JointJerkBackwardDifference uses backward differencing to estimate the third time derivative of the joint state. More...
#include <joint_jerk_backward_difference.h>
Public Member Functions | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW void | AssignScene (ScenePtr scene) override |
void | SetPreviousJointState (Eigen::VectorXdRefConst joint_state) |
Logs previous joint state. SetPreviousJointState must be called after solve is called in a Python/C++ script is called to ensure the time-derivatives are appropriately approximated. Each previous joint state is pushed back by collumn and the given joint_state is placed in q_.col(0). Finally, we compute the new qbd_. 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 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< JointJerkBackwardDifferenceInitializer > | |
std::vector< Initializer > | GetAllTemplates () const override |
Initializer | GetInitializerTemplate () override |
const JointJerkBackwardDifferenceInitializer & | GetParameters () const |
virtual void | Instantiate (const JointJerkBackwardDifferenceInitializer &init) |
void | InstantiateInternal (const Initializer &init) override |
Private Attributes | |
Eigen::Vector3d | backward_difference_params_ |
Binomial cooeficient parameters. More... | |
Eigen::MatrixXd | I_ |
Identity matrix. More... | |
int | N_ |
Number of dofs for robot. More... | |
Eigen::MatrixXd | q_ |
Log of previous three joint states. More... | |
Eigen::VectorXd | qbd_ |
x+qbd_ is a simplifed estimate of the third time derivative. 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< JointJerkBackwardDifferenceInitializer > | |
JointJerkBackwardDifferenceInitializer | parameters_ |
Time-derivative estimation by backward differencing. JointJerkBackwardDifference uses backward differencing to estimate the third time derivative of the joint state.
For more information see: http://mathworld.wolfram.com/BackwardDifference.html
Here, x+qbd_ represents the simplified estimate of the third time derivative.
Definition at line 49 of file joint_jerk_backward_difference.h.
|
overridevirtual |
Reimplemented from exotica::TaskMap.
Definition at line 36 of file joint_jerk_backward_difference.cpp.
void exotica::JointJerkBackwardDifference::SetPreviousJointState | ( | Eigen::VectorXdRefConst | joint_state | ) |
Logs previous joint state. SetPreviousJointState must be called after solve is called in a Python/C++ script is called to ensure the time-derivatives are appropriately approximated. Each previous joint state is pushed back by collumn and the given joint_state is placed in q_.col(0). Finally, we compute the new qbd_.
Definition at line 69 of file joint_jerk_backward_difference.cpp.
|
overridevirtual |
Implements exotica::TaskMap.
Definition at line 102 of file joint_jerk_backward_difference.cpp.
|
overridevirtual |
Implements exotica::TaskMap.
Definition at line 83 of file joint_jerk_backward_difference.cpp.
|
overridevirtual |
Reimplemented from exotica::TaskMap.
Definition at line 92 of file joint_jerk_backward_difference.cpp.
|
private |
Binomial cooeficient parameters.
Definition at line 70 of file joint_jerk_backward_difference.h.
|
private |
Identity matrix.
Definition at line 73 of file joint_jerk_backward_difference.h.
|
private |
Number of dofs for robot.
Definition at line 69 of file joint_jerk_backward_difference.h.
|
private |
Log of previous three joint states.
Definition at line 71 of file joint_jerk_backward_difference.h.
|
private |
x+qbd_ is a simplifed estimate of the third time derivative.
Definition at line 72 of file joint_jerk_backward_difference.h.