Constraint to specify Cartesian goal orientation (XYZ rotation) More...
#include <goal_orientation.h>
Public Member Functions | |
virtual Eigen::VectorXd | calcError () |
Rotation to get from current orientation to goal orientation Resolve into primary vectors (x,y,z) of base coordinate system Each element is multiplied by corresponding element in weight_. | |
virtual Eigen::MatrixXd | calcJacobian () |
Jacobian is the last three rows of standard jacobian (in base frame). Equivalent to each axis of rotation expressed in base frame coordinates. Each row is scaled by the corresponding element of weight_. | |
virtual bool | checkStatus () const |
Checks termination criteria Termination criteria for this constraint is that angle error is below threshold. | |
Eigen::Vector3d | getWeight () |
Getter for weight_. | |
GoalOrientation () | |
virtual void | reset () |
Resets constraint. Use this before performing new IK request. | |
void | setTolerance (double tol) |
Setter for tolerance (termination criteria) | |
void | setWeight (const Eigen::Vector3d &weight) |
Setter for weight_. | |
virtual void | update (const SolverState &state) |
Update internal state of constraint (overrides constraint::update) Sets current rotation error. | |
virtual | ~GoalOrientation () |
Static Public Member Functions | |
static double | calcAngle (const Eigen::Affine3d &p1, const Eigen::Affine3d &p2) |
Shortest angle between current orientation and goal orientation. | |
static Eigen::Vector3d | calcAngleError (const Eigen::Affine3d &p1, const Eigen::Affine3d &p2) |
Calculate 3-element rotation vector necessary to rotate pose p1 into pose p2. | |
Protected Attributes | |
double | rot_err_ |
double | rot_err_tol_ |
Eigen::Vector3d | weight_ |
Constraint to specify Cartesian goal orientation (XYZ rotation)
Definition at line 33 of file goal_orientation.h.
Definition at line 31 of file goal_orientation.cpp.
virtual constrained_ik::constraints::GoalOrientation::~GoalOrientation | ( | ) | [inline, virtual] |
Definition at line 37 of file goal_orientation.h.
double constrained_ik::constraints::GoalOrientation::calcAngle | ( | const Eigen::Affine3d & | p1, |
const Eigen::Affine3d & | p2 | ||
) | [static] |
Shortest angle between current orientation and goal orientation.
p1 | Current pose |
p2 | Goal pose |
Definition at line 35 of file goal_orientation.cpp.
Eigen::Vector3d constrained_ik::constraints::GoalOrientation::calcAngleError | ( | const Eigen::Affine3d & | p1, |
const Eigen::Affine3d & | p2 | ||
) | [static] |
Calculate 3-element rotation vector necessary to rotate pose p1 into pose p2.
p1 | Current pose |
p2 | Goal pose |
Definition at line 41 of file goal_orientation.cpp.
Eigen::VectorXd constrained_ik::constraints::GoalOrientation::calcError | ( | ) | [virtual] |
Rotation to get from current orientation to goal orientation Resolve into primary vectors (x,y,z) of base coordinate system Each element is multiplied by corresponding element in weight_.
Implements constrained_ik::Constraint.
Reimplemented in constrained_ik::constraints::GoalToolOrientation.
Definition at line 48 of file goal_orientation.cpp.
Eigen::MatrixXd constrained_ik::constraints::GoalOrientation::calcJacobian | ( | ) | [virtual] |
Jacobian is the last three rows of standard jacobian (in base frame). Equivalent to each axis of rotation expressed in base frame coordinates. Each row is scaled by the corresponding element of weight_.
Implements constrained_ik::Constraint.
Reimplemented in constrained_ik::constraints::GoalToolOrientation.
Definition at line 57 of file goal_orientation.cpp.
bool constrained_ik::constraints::GoalOrientation::checkStatus | ( | ) | const [virtual] |
Checks termination criteria Termination criteria for this constraint is that angle error is below threshold.
Reimplemented from constrained_ik::Constraint.
Definition at line 72 of file goal_orientation.cpp.
Eigen::Vector3d constrained_ik::constraints::GoalOrientation::getWeight | ( | ) | [inline] |
void constrained_ik::constraints::GoalOrientation::reset | ( | ) | [virtual] |
Resets constraint. Use this before performing new IK request.
Reimplemented from constrained_ik::Constraint.
Definition at line 81 of file goal_orientation.cpp.
void constrained_ik::constraints::GoalOrientation::setTolerance | ( | double | tol | ) | [inline] |
Setter for tolerance (termination criteria)
tol | Value to assign to tol_ |
Definition at line 85 of file goal_orientation.h.
void constrained_ik::constraints::GoalOrientation::setWeight | ( | const Eigen::Vector3d & | weight | ) | [inline] |
Setter for weight_.
weight | Value to assign to weight_ |
Definition at line 90 of file goal_orientation.h.
void constrained_ik::constraints::GoalOrientation::update | ( | const SolverState & | state | ) | [virtual] |
Update internal state of constraint (overrides constraint::update) Sets current rotation error.
state | SolverState holding current state of IK solver |
Reimplemented from constrained_ik::Constraint.
Definition at line 87 of file goal_orientation.cpp.
double constrained_ik::constraints::GoalOrientation::rot_err_ [protected] |
Definition at line 100 of file goal_orientation.h.
double constrained_ik::constraints::GoalOrientation::rot_err_tol_ [protected] |
Definition at line 99 of file goal_orientation.h.
Eigen::Vector3d constrained_ik::constraints::GoalOrientation::weight_ [protected] |
Definition at line 101 of file goal_orientation.h.