Constraint to specify cartesian tool goal pointing (XYZRP) More...
#include <goal_tool_pointing.h>
Classes | |
struct | GoalToolPointingData |
This structure stores constraint data. More... | |
Public Member Functions | |
virtual Eigen::VectorXd | calcError (const GoalToolPointingData &cdata) const |
Direction vector from current position to goal position Expressed in tool coordinate system Each element is multiplied by corresponding element in weight_. | |
virtual Eigen::MatrixXd | calcJacobian (const GoalToolPointingData &cdata) const |
Jacobian is first five rows of tool jacobian (expressed in tool 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 GoalToolPointingData &cdata) const |
Checks termination criteria Termination criteria for this constraint is that positional and rotational error is below threshold. | |
constrained_ik::ConstraintResults | evalConstraint (const SolverState &state) const override |
see base class for documentation | |
virtual double | getOrientationTolerance () const |
Getter for rot_err_tol_. | |
virtual double | getPositionTolerance () const |
Getter for pos_err_tol_. | |
virtual Eigen::Matrix< double, 5, 1 > | getWeight () const |
Getter for weight_. | |
void | loadParameters (const XmlRpc::XmlRpcValue &constraint_xml) override |
see base class for documentation | |
virtual void | setOrientationTolerance (const double &orientation_tolerance) |
Setter for rot_err_tol_. | |
virtual void | setPositionTolerance (const double &position_tolerance) |
Setter for pos_err_tol_. | |
virtual void | setWeight (const Eigen::Matrix< double, 5, 1 > &weight) |
Setter for weight_. | |
Protected Attributes | |
double | pos_err_tol_ |
termination criteria | |
double | rot_err_tol_ |
termination criteria | |
Eigen::Matrix< double, 5, 5 > | weight_ |
weights used to scale the jocabian and error |
Constraint to specify cartesian tool goal pointing (XYZRP)
Definition at line 43 of file goal_tool_pointing.h.
Eigen::VectorXd constrained_ik::constraints::GoalToolPointing::calcError | ( | const GoalToolPointingData & | cdata | ) | const [virtual] |
Direction vector from current position to goal position Expressed in tool coordinate system Each element is multiplied by corresponding element in weight_.
cdata | The constraint specific data. |
Definition at line 59 of file goal_tool_pointing.cpp.
Eigen::MatrixXd constrained_ik::constraints::GoalToolPointing::calcJacobian | ( | const GoalToolPointingData & | cdata | ) | const [virtual] |
Jacobian is first five rows of tool jacobian (expressed in tool 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. |
Definition at line 72 of file goal_tool_pointing.cpp.
bool constrained_ik::constraints::GoalToolPointing::checkStatus | ( | const GoalToolPointingData & | cdata | ) | const [virtual] |
Checks termination criteria Termination criteria for this constraint is that positional and rotational error is below threshold.
cdata | The constraint specific data. |
Definition at line 91 of file goal_tool_pointing.cpp.
virtual double constrained_ik::constraints::GoalToolPointing::getOrientationTolerance | ( | ) | const [inline, virtual] |
virtual double constrained_ik::constraints::GoalToolPointing::getPositionTolerance | ( | ) | const [inline, virtual] |
virtual Eigen::Matrix<double, 5, 1> constrained_ik::constraints::GoalToolPointing::getWeight | ( | ) | const [inline, virtual] |
virtual void constrained_ik::constraints::GoalToolPointing::setOrientationTolerance | ( | const double & | orientation_tolerance | ) | [inline, virtual] |
Setter for rot_err_tol_.
orientation_tolerance | Value to assign to rot_err_tol_ |
Definition at line 126 of file goal_tool_pointing.h.
virtual void constrained_ik::constraints::GoalToolPointing::setPositionTolerance | ( | const double & | position_tolerance | ) | [inline, virtual] |
Setter for pos_err_tol_.
position_tolerance | Value to assign to pos_err_tol_ |
Definition at line 114 of file goal_tool_pointing.h.
virtual void constrained_ik::constraints::GoalToolPointing::setWeight | ( | const Eigen::Matrix< double, 5, 1 > & | weight | ) | [inline, virtual] |
Setter for weight_.
weight | Value to assign to weight_ |
Definition at line 102 of file goal_tool_pointing.h.