Time-derivative estimation by backward differencing. JointVelocityBackwardDifference uses backward differencing to estimate the first time derivative of the joint state. More...
#include <joint_velocity_backward_difference.h>
Public Member Functions | |
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. The new joint_state is set to q_. 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 |
![]() | |
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) |
![]() | |
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 () |
![]() | |
virtual std::vector< Initializer > | GetAllTemplates () const=0 |
InstantiableBase ()=default | |
virtual | ~InstantiableBase ()=default |
![]() | |
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 | |
double | backward_difference_params_ |
Binomial coefficient parameters. More... | |
Eigen::MatrixXd | I_ |
Identity matrix. More... | |
int | N_ |
Number of dofs for robot. More... | |
Eigen::VectorXd | q_ |
Log of previous joint state. More... | |
Eigen::VectorXd | qbd_ |
x+qbd_ is a simplified estimate of the first time derivative. More... | |
Additional Inherited Members | |
![]() | |
int | id |
bool | is_used |
std::vector< KinematicSolution > | kinematics |
int | length |
int | length_jacobian |
int | start |
int | start_jacobian |
![]() | |
bool | debug_ |
std::string | ns_ |
std::string | object_name_ |
![]() | |
std::vector< KinematicFrameRequest > | frames_ |
ScenePtr | scene_ |
![]() | |
C | parameters_ |
Time-derivative estimation by backward differencing. JointVelocityBackwardDifference uses backward differencing to estimate the first 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 first time derivative.
Definition at line 48 of file joint_velocity_backward_difference.h.
|
overridevirtual |
Reimplemented from exotica::TaskMap.
Definition at line 36 of file joint_velocity_backward_difference.cpp.
void exotica::JointVelocityBackwardDifference::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. The new joint_state is set to q_. Finally, we compute the new qbd_.
Definition at line 62 of file joint_velocity_backward_difference.cpp.
|
overridevirtual |
Implements exotica::TaskMap.
Definition at line 94 of file joint_velocity_backward_difference.cpp.
|
overridevirtual |
Implements exotica::TaskMap.
Definition at line 74 of file joint_velocity_backward_difference.cpp.
|
overridevirtual |
Reimplemented from exotica::TaskMap.
Definition at line 84 of file joint_velocity_backward_difference.cpp.
|
private |
Binomial coefficient parameters.
Definition at line 64 of file joint_velocity_backward_difference.h.
|
private |
Identity matrix.
Definition at line 68 of file joint_velocity_backward_difference.h.
|
private |
Number of dofs for robot.
Definition at line 65 of file joint_velocity_backward_difference.h.
|
private |
Log of previous joint state.
Definition at line 66 of file joint_velocity_backward_difference.h.
|
private |
x+qbd_ is a simplified estimate of the first time derivative.
Definition at line 67 of file joint_velocity_backward_difference.h.