Classes | Public Member Functions | Protected Member Functions | Protected Attributes
constrained_ik::constraints::AvoidJointLimits Class Reference

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>

Inheritance diagram for constrained_ik::constraints::AvoidJointLimits:
Inheritance graph
[legend]

List of all members.

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< LimitsTlimits_
double threshold_
double weight_

Detailed Description

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.


Constructor & Destructor Documentation

Definition at line 44 of file avoid_joint_limits.h.

Definition at line 45 of file avoid_joint_limits.h.


Member Function Documentation

Creates vector representing velocity error term corresponding to calcJacobian()

Returns:
VectorXd of joint velocities for joint limit avoidance

Implements constrained_ik::Constraint.

Definition at line 37 of file avoid_joint_limits.cpp.

Creates jacobian rows corresponding to joint velocity limit avoidance Each limited joint gets a 0 row with a 1 in that joint's column.

Returns:
Pseudo-Identity scaled by weight_

Implements constrained_ik::Constraint.

Definition at line 71 of file avoid_joint_limits.cpp.

Checks termination criteria There are no termination criteria for this constraint.

Returns:
True

Reimplemented from constrained_ik::Constraint.

Definition at line 89 of file avoid_joint_limits.cpp.

getter for weight_

Returns:
weight_

Definition at line 86 of file avoid_joint_limits.h.

Initialize constraint (overrides Constraint::init) Initializes internal limit variables Should be called before using class.

Parameters:
ikPointer to Constrained_IK used for base-class init

Reimplemented from constrained_ik::Constraint.

Definition at line 98 of file avoid_joint_limits.cpp.

Check if a given joint is near its lower limit.

Parameters:
idxIndex of joint
Returns:
True if joint position is within threshold of lower limit

Definition at line 108 of file avoid_joint_limits.cpp.

Check if a given joint is near its upper limit.

Parameters:
idxIndex of joint
Returns:
True if joint position is within threshold of upper limit

Definition at line 115 of file avoid_joint_limits.cpp.

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_

Parameters:
weightValue to set weight_ to

Definition at line 91 of file avoid_joint_limits.h.

Update internal state of constraint (overrides constraint::update) Sets which joints are near limits.

Parameters:
stateSolverState holding current state of IK solver

Reimplemented from constrained_ik::Constraint.

Definition at line 140 of file avoid_joint_limits.cpp.


Member Data Documentation

Definition at line 121 of file avoid_joint_limits.h.

Definition at line 120 of file avoid_joint_limits.h.

Definition at line 123 of file avoid_joint_limits.h.

Definition at line 122 of file avoid_joint_limits.h.


The documentation for this class was generated from the following files:


constrained_ik
Author(s): Chris Lewis , Jeremy Zoss , Dan Solomon
autogenerated on Mon Oct 6 2014 00:52:27