Constraint to avoid joint position limits. More...
#include <avoid_joint_limits.h>
Classes | |
struct | AvoidJointLimitsData |
This structure stores constraint data. More... | |
struct | LimitsT |
Stores joint limit constraint data for a single joint. More... | |
Public Member Functions | |
virtual Eigen::VectorXd | calcError (const AvoidJointLimitsData &cdata) const |
Creates vector representing velocity error term corresponding to calcJacobian() | |
virtual Eigen::MatrixXd | calcJacobian (const AvoidJointLimitsData &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 AvoidJointLimitsData &cdata) const |
Checks termination criteria There are no termination criteria for this constraint. | |
constrained_ik::ConstraintResults | evalConstraint (const SolverState &state) const override |
see base class for documentation | |
virtual double | getThreshold () const |
getter for threshold_ | |
virtual double | getWeight () const |
getter for weight_ | |
void | init (const Constrained_IK *ik) override |
Initialize constraint (overrides Constraint::init) Initializes internal limit variables Should be called before using class. | |
void | loadParameters (const XmlRpc::XmlRpcValue &constraint_xml) override |
see base class for documentation | |
virtual void | setThreshold (const double &threshold) |
setter for threshold_ | |
virtual void | setWeight (const double &weight) |
setter for weight_ | |
Protected Attributes | |
std::vector< LimitsT > | limits_ |
vector holding joint limit data | |
double | threshold_ |
threshold (% of range) at which to engage limit avoidance | |
double | weight_ |
weights used to scale the jocabian and error |
Constraint to avoid joint position limits.
Using cubic velocity ramp, it pushes each joint away from its limits, with a maximimum velocity of 2*threshold*(joint range). Only affects joints that are within theshold of joint limit.
Definition at line 52 of file avoid_joint_limits.h.
Eigen::VectorXd constrained_ik::constraints::AvoidJointLimits::calcError | ( | const AvoidJointLimitsData & | cdata | ) | const [virtual] |
Creates vector representing velocity error term corresponding to calcJacobian()
cdata | The constraint specific data. |
Definition at line 61 of file avoid_joint_limits.cpp.
Eigen::MatrixXd constrained_ik::constraints::AvoidJointLimits::calcJacobian | ( | const AvoidJointLimitsData & | 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 95 of file avoid_joint_limits.cpp.
virtual bool constrained_ik::constraints::AvoidJointLimits::checkStatus | ( | const AvoidJointLimitsData & | cdata | ) | const [inline, virtual] |
Checks termination criteria There are no termination criteria for this constraint.
cdata | The constraint specific data. |
Definition at line 155 of file avoid_joint_limits.h.
virtual double constrained_ik::constraints::AvoidJointLimits::getThreshold | ( | ) | const [inline, virtual] |
virtual double constrained_ik::constraints::AvoidJointLimits::getWeight | ( | ) | const [inline, virtual] |
void constrained_ik::constraints::AvoidJointLimits::init | ( | const Constrained_IK * | ik | ) | [override, virtual] |
Initialize constraint (overrides Constraint::init) Initializes internal limit variables Should be called before using class.
ik | Pointer to Constrained_IK used for base-class init |
Reimplemented from constrained_ik::Constraint.
Definition at line 113 of file avoid_joint_limits.cpp.
virtual void constrained_ik::constraints::AvoidJointLimits::setThreshold | ( | const double & | threshold | ) | [inline, virtual] |
setter for threshold_
threshold | Value to set threshold_ to |
Definition at line 179 of file avoid_joint_limits.h.
virtual void constrained_ik::constraints::AvoidJointLimits::setWeight | ( | const double & | weight | ) | [inline, virtual] |
setter for weight_
weight | Value to set weight_ to |
Definition at line 167 of file avoid_joint_limits.h.