Constraint to specify cartesian goal position (XYZ) More...
#include <goal_position.h>
Classes | |
struct | GoalPositionData |
This structure stores constraint data. More... | |
Public Member Functions | |
virtual Eigen::VectorXd | calcError (const GoalPositionData &cdata) const |
Direction vector from current position to goal position Expressed in base coordinate system Each element is multiplied by corresponding element in weight_. | |
virtual Eigen::MatrixXd | calcJacobian (const GoalPositionData &cdata) const |
Jacobian is first three rows of standard jacobian (expressed in base frame). Equivalent to each axis of rotation crossed with vector from joint to chain tip. Each row is scaled by the corresponding element of weight_. | |
virtual bool | checkStatus (const GoalPositionData &cdata) const |
Checks termination criteria Termination criteria for this constraint is that positional error is below threshold. | |
constrained_ik::ConstraintResults | evalConstraint (const SolverState &state) const override |
see base class for documentation | |
virtual double | getTolerance () const |
Getter for the positional convergance tolerance. | |
virtual Eigen::Vector3d | getWeight () const |
Getter for weight_. | |
void | loadParameters (const XmlRpc::XmlRpcValue &constraint_xml) override |
see base class for documentation | |
virtual void | setTolerance (const double &tol) |
Setter for positional convergance tolerance. | |
virtual void | setWeight (const Eigen::Vector3d &weight) |
Setter for weight_. | |
Static Public Member Functions | |
static double | calcDistance (const Eigen::Affine3d &p1, const Eigen::Affine3d &p2) |
Calculates distance between two frames. | |
Protected Attributes | |
double | pos_err_tol_ |
termination criteria | |
Eigen::Vector3d | weight_ |
weights used to scale the jocabian and error |
Constraint to specify cartesian goal position (XYZ)
Definition at line 43 of file goal_position.h.
double constrained_ik::constraints::GoalPosition::calcDistance | ( | const Eigen::Affine3d & | p1, |
const Eigen::Affine3d & | p2 | ||
) | [static] |
Calculates distance between two frames.
p1 | Current frame |
p2 | Goal frame |
Definition at line 84 of file goal_position.cpp.
Eigen::VectorXd constrained_ik::constraints::GoalPosition::calcError | ( | const GoalPositionData & | cdata | ) | const [virtual] |
Direction vector from current position to goal position Expressed in base coordinate system Each element is multiplied by corresponding element in weight_.
cdata | The constraint specific data. |
Reimplemented in constrained_ik::constraints::ToolPosition.
Definition at line 58 of file goal_position.cpp.
Eigen::MatrixXd constrained_ik::constraints::GoalPosition::calcJacobian | ( | const GoalPositionData & | cdata | ) | const [virtual] |
Jacobian is first three rows of standard jacobian (expressed in base frame). Equivalent to each axis of rotation crossed with vector from joint to chain tip. Each row is scaled by the corresponding element of weight_.
cdata | The constraint specific data. |
Reimplemented in constrained_ik::constraints::ToolPosition.
Definition at line 69 of file goal_position.cpp.
bool constrained_ik::constraints::GoalPosition::checkStatus | ( | const GoalPositionData & | cdata | ) | const [virtual] |
Checks termination criteria Termination criteria for this constraint is that positional error is below threshold.
cdata | The constraint specific data. |
Definition at line 89 of file goal_position.cpp.
virtual double constrained_ik::constraints::GoalPosition::getTolerance | ( | ) | const [inline, virtual] |
Getter for the positional convergance tolerance.
Definition at line 117 of file goal_position.h.
virtual Eigen::Vector3d constrained_ik::constraints::GoalPosition::getWeight | ( | ) | const [inline, virtual] |
virtual void constrained_ik::constraints::GoalPosition::setTolerance | ( | const double & | tol | ) | [inline, virtual] |
Setter for positional convergance tolerance.
tol | Value to assign to pos_err_tol |
Definition at line 123 of file goal_position.h.
virtual void constrained_ik::constraints::GoalPosition::setWeight | ( | const Eigen::Vector3d & | weight | ) | [inline, virtual] |
Setter for weight_.
weight | Value to assign to weight_ |
Definition at line 111 of file goal_position.h.