Constraint class 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. More...
#include <avoid_joint_limits.h>
Classes | |
struct | LimitsT |
Public Member Functions | |
AvoidJointLimits () | |
virtual Eigen::VectorXd | calcError () |
Creates vector representing velocity error term corresponding to calcJacobian() | |
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 There are no termination criteria for this constraint. | |
double | getWeight () |
getter for weight_ | |
virtual void | init (const Constrained_IK *ik) |
Initialize constraint (overrides Constraint::init) Initializes internal limit variables Should be called before using class. | |
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 limits. | |
virtual | ~AvoidJointLimits () |
Protected Member Functions | |
bool | nearLowerLimit (size_t idx) |
Check if a given joint is near its lower limit. | |
bool | nearUpperLimit (size_t idx) |
Check if a given joint is near its upper limit. | |
Protected Attributes | |
std::vector< int > | limited_joints_ |
std::vector< LimitsT > | limits_ |
double | threshold_ |
double | weight_ |
Constraint class 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 41 of file avoid_joint_limits.h.
Definition at line 44 of file avoid_joint_limits.h.
virtual constrained_ik::constraints::AvoidJointLimits::~AvoidJointLimits | ( | ) | [inline, virtual] |
Definition at line 45 of file avoid_joint_limits.h.
Eigen::VectorXd constrained_ik::constraints::AvoidJointLimits::calcError | ( | ) | [virtual] |
Creates vector representing velocity error term corresponding to calcJacobian()
Implements constrained_ik::Constraint.
Definition at line 37 of file avoid_joint_limits.cpp.
Eigen::MatrixXd constrained_ik::constraints::AvoidJointLimits::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 71 of file avoid_joint_limits.cpp.
bool constrained_ik::constraints::AvoidJointLimits::checkStatus | ( | ) | const [virtual] |
Checks termination criteria There are no termination criteria for this constraint.
Reimplemented from constrained_ik::Constraint.
Definition at line 89 of file avoid_joint_limits.cpp.
double constrained_ik::constraints::AvoidJointLimits::getWeight | ( | ) | [inline] |
void constrained_ik::constraints::AvoidJointLimits::init | ( | const Constrained_IK * | ik | ) | [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 98 of file avoid_joint_limits.cpp.
bool constrained_ik::constraints::AvoidJointLimits::nearLowerLimit | ( | size_t | idx | ) | [protected] |
Check if a given joint is near its lower limit.
idx | Index of joint |
Definition at line 108 of file avoid_joint_limits.cpp.
bool constrained_ik::constraints::AvoidJointLimits::nearUpperLimit | ( | size_t | idx | ) | [protected] |
Check if a given joint is near its upper limit.
idx | Index of joint |
Definition at line 115 of file avoid_joint_limits.cpp.
void constrained_ik::constraints::AvoidJointLimits::reset | ( | ) | [virtual] |
Resets constraint before new use. Call this method before beginning a new IK calculation.
Reimplemented from constrained_ik::Constraint.
Definition at line 123 of file avoid_joint_limits.cpp.
void constrained_ik::constraints::AvoidJointLimits::setWeight | ( | const double & | weight | ) | [inline] |
setter for weight_
weight | Value to set weight_ to |
Definition at line 91 of file avoid_joint_limits.h.
void constrained_ik::constraints::AvoidJointLimits::update | ( | const SolverState & | state | ) | [virtual] |
Update internal state of constraint (overrides constraint::update) Sets which joints are near limits.
state | SolverState holding current state of IK solver |
Reimplemented from constrained_ik::Constraint.
Definition at line 140 of file avoid_joint_limits.cpp.
std::vector<int> constrained_ik::constraints::AvoidJointLimits::limited_joints_ [protected] |
Definition at line 121 of file avoid_joint_limits.h.
std::vector<LimitsT> constrained_ik::constraints::AvoidJointLimits::limits_ [protected] |
Definition at line 120 of file avoid_joint_limits.h.
double constrained_ik::constraints::AvoidJointLimits::threshold_ [protected] |
Definition at line 123 of file avoid_joint_limits.h.
double constrained_ik::constraints::AvoidJointLimits::weight_ [protected] |
Definition at line 122 of file avoid_joint_limits.h.