Public Member Functions | Protected Attributes
constrained_ik::constraints::JointVelLimits Class Reference

Constraint to avoid joint velocity limits. More...

#include <joint_vel_limits.h>

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

List of all members.

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_

Detailed Description

Constraint to avoid joint velocity limits.

Definition at line 38 of file joint_vel_limits.h.


Constructor & Destructor Documentation

Definition at line 37 of file joint_vel_limits.cpp.

Definition at line 42 of file joint_vel_limits.h.


Member Function Documentation

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)

Returns:
VectorXd of joint velocities for joint velocity limit avoidance

Implements constrained_ik::Constraint.

Definition at line 42 of file joint_vel_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 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.

Returns:
True if no joints violating veloity limit

Reimplemented from constrained_ik::Constraint.

Definition at line 61 of file joint_vel_limits.h.

getter for weight_

Returns:
weight_

Definition at line 84 of file joint_vel_limits.h.

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

Parameters:
ikPointer to Constrained_IK used for base-class init

Reimplemented from constrained_ik::Constraint.

Definition at line 83 of file joint_vel_limits.cpp.

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_

Parameters:
weightValue to set weight_ to

Definition at line 89 of file joint_vel_limits.h.

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

Parameters:
stateSolverState holding current state of IK solver

Reimplemented from constrained_ik::Constraint.

Definition at line 111 of file joint_vel_limits.cpp.


Member Data Documentation

Definition at line 93 of file joint_vel_limits.h.

Definition at line 89 of file joint_vel_limits.h.

Definition at line 94 of file joint_vel_limits.h.

Definition at line 93 of file joint_vel_limits.h.

Definition at line 94 of file joint_vel_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