Constraint to avoid joint velocity limits. More...
#include <joint_vel_limits.h>
Classes | |
struct | JointVelLimitsData |
This structure stores constraint data. More... | |
Public Member Functions | |
virtual Eigen::VectorXd | calcError (const JointVelLimitsData &cdata) const |
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 (const JointVelLimitsData &cdata) const |
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 JointVelLimitsData &cdata) const |
Checks termination criteria This constraint is satisfied if no joints are beyond velocity limits. | |
constrained_ik::ConstraintResults | evalConstraint (const SolverState &state) const override |
See base class for documentation. | |
virtual double | getTimestep () const |
getter for timestep_ | |
virtual double | getWeight () const |
getter for weight_ | |
void | init (const Constrained_IK *ik) override |
Initialize constraint (overrides Constraint::init) Initializes internal velocity limit variable Should be called before using class. | |
void | loadParameters (const XmlRpc::XmlRpcValue &constraint_xml) override |
See base class for documentation. | |
virtual void | setTimestep (const double ×tep) |
setter for timestep_ | |
virtual void | setWeight (const double &weight) |
setter for weight_ | |
Protected Attributes | |
double | timestep_ |
timestep used to calculate joint velocities | |
Eigen::VectorXd | vel_limits_ |
joint velocity limits | |
double | weight_ |
weights used to scale the jocabian and error |
Constraint to avoid joint velocity limits.
Need to make the joint velocity limit configurable
This class should be renamed to AvoidJointVelLimits
Definition at line 45 of file joint_vel_limits.h.
Eigen::VectorXd constrained_ik::constraints::JointVelLimits::calcError | ( | const JointVelLimitsData & | cdata | ) | const [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)
cdata | The constraint specific data. |
Definition at line 59 of file joint_vel_limits.cpp.
Eigen::MatrixXd constrained_ik::constraints::JointVelLimits::calcJacobian | ( | const JointVelLimitsData & | cdata | ) | const [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.
cdata | The constraint specific data. |
Definition at line 82 of file joint_vel_limits.cpp.
virtual bool constrained_ik::constraints::JointVelLimits::checkStatus | ( | const JointVelLimitsData & | cdata | ) | const [inline, virtual] |
Checks termination criteria This constraint is satisfied if no joints are beyond velocity limits.
cdata | The constraint specific data. |
Definition at line 100 of file joint_vel_limits.h.
virtual double constrained_ik::constraints::JointVelLimits::getTimestep | ( | ) | const [inline, virtual] |
virtual double constrained_ik::constraints::JointVelLimits::getWeight | ( | ) | const [inline, virtual] |
void constrained_ik::constraints::JointVelLimits::init | ( | const Constrained_IK * | ik | ) | [override, 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 100 of file joint_vel_limits.cpp.
virtual void constrained_ik::constraints::JointVelLimits::setTimestep | ( | const double & | timestep | ) | [inline, virtual] |
setter for timestep_
timestep | Value to set timestep_ to |
Definition at line 124 of file joint_vel_limits.h.
virtual void constrained_ik::constraints::JointVelLimits::setWeight | ( | const double & | weight | ) | [inline, virtual] |
setter for weight_
weight | Value to set weight_ to |
Definition at line 112 of file joint_vel_limits.h.