A wrapper class around the IK planner.
This class improves IK's usability by handling constraint relaxing and multiple initial guesses internally.
#include <drake/multibody/inverse_kinematics/constraint_relaxing_ik.h>
Classes | |
struct | IkCartesianWaypoint |
Cartesian waypoint. More... | |
Public Member Functions | |
ConstraintRelaxingIk (const std::string &model_path, const std::string &end_effector_link_name) | |
Constructor. More... | |
void | SetEndEffector (const std::string &link_name) |
Sets end effector to link_name . More... | |
bool | PlanSequentialTrajectory (const std::vector< IkCartesianWaypoint > &waypoints, const VectorX< double > &q_current, std::vector< Eigen::VectorXd > *q_sol, const std::function< bool(int)> &keep_going={}) |
Generates IK solutions for each waypoint sequentially. More... | |
Does not allow copy, move, or assignment | |
ConstraintRelaxingIk (const ConstraintRelaxingIk &)=delete | |
ConstraintRelaxingIk & | operator= (const ConstraintRelaxingIk &)=delete |
ConstraintRelaxingIk (ConstraintRelaxingIk &&)=delete | |
ConstraintRelaxingIk & | operator= (ConstraintRelaxingIk &&)=delete |
|
delete |
|
delete |
ConstraintRelaxingIk | ( | const std::string & | model_path, |
const std::string & | end_effector_link_name | ||
) |
Constructor.
Instantiates an internal MultibodyPlant from model_path
.
model_path | Path to the model file. |
end_effector_link_name | Link name of the end effector. |
|
delete |
|
delete |
bool PlanSequentialTrajectory | ( | const std::vector< IkCartesianWaypoint > & | waypoints, |
const VectorX< double > & | q_current, | ||
std::vector< Eigen::VectorXd > * | q_sol, | ||
const std::function< bool(int)> & | keep_going = {} |
||
) |
Generates IK solutions for each waypoint sequentially.
For waypoint wp_i, the IK tries to solve q_i that satisfies the end effector constraints in wp_i and minimizes the squared difference to q_{i-1}, where q_{i-1} is the solution to the previous wp_{i-1}. q_{i-1} = q_current
when i = 0. This function internally does constraint relaxing and initial condition guessing if necessary.
Note that q_current
is inserted at the beginning of q_sol
.
waypoints | A sequence of desired waypoints. | |
q_current | The initial generalized position. | |
[out] | q_sol | Results. |
keep_going | Optional callback to allow for cancellation. When given, this function will be called prior to every IK solve; if it returns false, the PlanSequentialTrajectory will stop and return false. The function is passed the index of the waypoint currently being solved. This can be used to enable timeouts for difficult plans. |
void SetEndEffector | ( | const std::string & | link_name | ) |
Sets end effector to link_name
.