Constraint to avoid joint velocity limits. More...
#include <joint_vel_limits.h>

Public Member Functions | |
| virtual Eigen::VectorXd | calcError () |
| Creates vector representing velocity error term corresponding to calcJacobian() Velocity error is difference between current velocity and velocity limit (only applicable for joints outside velocity limits) | |
| virtual Eigen::MatrixXd | calcJacobian () |
| Creates jacobian rows corresponding to joint velocity limit avoidance Each limited joint gets a 0 row with a 1 in that joint's column. | |
| virtual bool | checkStatus () const |
| Checks termination criteria This constraint is satisfied if no joints are beyond velocity limits. | |
| double | getWeight () |
| getter for weight_ | |
| virtual void | init (const Constrained_IK *ik) |
| Initialize constraint (overrides Constraint::init) Initializes internal velocity limit variable Should be called before using class. | |
| JointVelLimits () | |
| virtual void | reset () |
| Resets constraint before new use. Call this method before beginning a new IK calculation. | |
| void | setWeight (const double &weight) |
| setter for weight_ | |
| virtual void | update (const SolverState &state) |
| Update internal state of constraint (overrides constraint::update) Sets which joints are near velocity limits. | |
| virtual | ~JointVelLimits () |
Protected Attributes | |
| Eigen::VectorXd | jvel_ |
| std::vector< int > | limited_joints_ |
| double | timestep_ |
| Eigen::VectorXd | vel_limits_ |
| double | weight_ |
Constraint to avoid joint velocity limits.
Definition at line 38 of file joint_vel_limits.h.
Definition at line 37 of file joint_vel_limits.cpp.
| virtual constrained_ik::constraints::JointVelLimits::~JointVelLimits | ( | ) | [inline, virtual] |
Definition at line 42 of file joint_vel_limits.h.
| Eigen::VectorXd constrained_ik::constraints::JointVelLimits::calcError | ( | ) | [virtual] |
Creates vector representing velocity error term corresponding to calcJacobian() Velocity error is difference between current velocity and velocity limit (only applicable for joints outside velocity limits)
Implements constrained_ik::Constraint.
Definition at line 42 of file joint_vel_limits.cpp.
| Eigen::MatrixXd constrained_ik::constraints::JointVelLimits::calcJacobian | ( | ) | [virtual] |
Creates jacobian rows corresponding to joint velocity limit avoidance Each limited joint gets a 0 row with a 1 in that joint's column.
Implements constrained_ik::Constraint.
Definition at line 65 of file joint_vel_limits.cpp.
| virtual bool constrained_ik::constraints::JointVelLimits::checkStatus | ( | ) | const [inline, virtual] |
Checks termination criteria This constraint is satisfied if no joints are beyond velocity limits.
Reimplemented from constrained_ik::Constraint.
Definition at line 61 of file joint_vel_limits.h.
| double constrained_ik::constraints::JointVelLimits::getWeight | ( | ) | [inline] |
| void constrained_ik::constraints::JointVelLimits::init | ( | const Constrained_IK * | ik | ) | [virtual] |
Initialize constraint (overrides Constraint::init) Initializes internal velocity limit variable Should be called before using class.
| ik | Pointer to Constrained_IK used for base-class init |
Reimplemented from constrained_ik::Constraint.
Definition at line 83 of file joint_vel_limits.cpp.
| void constrained_ik::constraints::JointVelLimits::reset | ( | ) | [virtual] |
Resets constraint before new use. Call this method before beginning a new IK calculation.
Reimplemented from constrained_ik::Constraint.
Definition at line 94 of file joint_vel_limits.cpp.
| void constrained_ik::constraints::JointVelLimits::setWeight | ( | const double & | weight | ) | [inline] |
setter for weight_
| weight | Value to set weight_ to |
Definition at line 89 of file joint_vel_limits.h.
| void constrained_ik::constraints::JointVelLimits::update | ( | const SolverState & | state | ) | [virtual] |
Update internal state of constraint (overrides constraint::update) Sets which joints are near velocity limits.
| state | SolverState holding current state of IK solver |
Reimplemented from constrained_ik::Constraint.
Definition at line 111 of file joint_vel_limits.cpp.
Eigen::VectorXd constrained_ik::constraints::JointVelLimits::jvel_ [protected] |
Definition at line 93 of file joint_vel_limits.h.
std::vector<int> constrained_ik::constraints::JointVelLimits::limited_joints_ [protected] |
Definition at line 89 of file joint_vel_limits.h.
double constrained_ik::constraints::JointVelLimits::timestep_ [protected] |
Definition at line 94 of file joint_vel_limits.h.
Eigen::VectorXd constrained_ik::constraints::JointVelLimits::vel_limits_ [protected] |
Definition at line 93 of file joint_vel_limits.h.
double constrained_ik::constraints::JointVelLimits::weight_ [protected] |
Definition at line 94 of file joint_vel_limits.h.