Constraint to specify Cartesian goal orientation (XYZ rotation) More...
#include <goal_orientation.h>
Classes | |
struct | GoalOrientationData |
This structure stores constraint data. More... | |
Public Member Functions | |
virtual Eigen::VectorXd | calcError (const GoalOrientationData &cdata) const |
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 (const GoalOrientationData &cdata) const |
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 GoalOrientationData &cdata) const |
Checks termination criteria Termination criteria for this constraint is that angle error is below threshold. | |
constrained_ik::ConstraintResults | evalConstraint (const SolverState &state) const override |
see base class for documentation | |
virtual double | getTolerance () const |
Getter for rot_err_tol_. | |
virtual Eigen::Vector3d | getWeight () const |
Getter for weight_. | |
void | loadParameters (const XmlRpc::XmlRpcValue &constraint_xml) override |
see base class for documentation | |
virtual void | setTolerance (double tol) |
Setter for tolerance (termination criteria) | |
virtual void | setWeight (const Eigen::Vector3d &weight) |
Setter for weight_. | |
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_tol_ |
termination criteria | |
Eigen::Vector3d | weight_ |
weights used to scale the jocabian and error |
Constraint to specify Cartesian goal orientation (XYZ rotation)
Definition at line 43 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 58 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 64 of file goal_orientation.cpp.
Eigen::VectorXd constrained_ik::constraints::GoalOrientation::calcError | ( | const GoalOrientationData & | cdata | ) | const [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_.
cdata | The constraint specific data. |
Reimplemented in constrained_ik::constraints::GoalToolOrientation.
Definition at line 71 of file goal_orientation.cpp.
Eigen::MatrixXd constrained_ik::constraints::GoalOrientation::calcJacobian | ( | const GoalOrientationData & | cdata | ) | const [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_.
cdata | The constraint specific data. |
Reimplemented in constrained_ik::constraints::GoalToolOrientation.
Definition at line 80 of file goal_orientation.cpp.
bool constrained_ik::constraints::GoalOrientation::checkStatus | ( | const GoalOrientationData & | cdata | ) | const [virtual] |
Checks termination criteria Termination criteria for this constraint is that angle error is below threshold.
cdata | The constraint specific data. |
Definition at line 95 of file goal_orientation.cpp.
virtual double constrained_ik::constraints::GoalOrientation::getTolerance | ( | ) | const [inline, virtual] |
virtual Eigen::Vector3d constrained_ik::constraints::GoalOrientation::getWeight | ( | ) | const [inline, virtual] |
virtual void constrained_ik::constraints::GoalOrientation::setTolerance | ( | double | tol | ) | [inline, virtual] |
Setter for tolerance (termination criteria)
tol | Value to assign to tol_ |
Definition at line 130 of file goal_orientation.h.
virtual void constrained_ik::constraints::GoalOrientation::setWeight | ( | const Eigen::Vector3d & | weight | ) | [inline, virtual] |
Setter for weight_.
weight | Value to assign to weight_ |
Definition at line 118 of file goal_orientation.h.