#include <gradient_projection_method_solver.h>
Public Member Functions | |
GradientProjectionMethodSolver (const TwistControllerParams ¶ms, const LimiterParams &limiter_params, TaskStackController_t &task_stack_controller) | |
virtual Eigen::MatrixXd | solve (const Vector6d_t &in_cart_velocities, const JointStates &joint_states) |
virtual | ~GradientProjectionMethodSolver () |
![]() | |
void | clearConstraints () |
ConstraintSolver (const TwistControllerParams ¶ms, const LimiterParams &limiter_params, TaskStackController_t &task_stack_controller) | |
void | setConstraints (std::set< ConstraintBase_t > &constraints) |
void | setDamping (boost::shared_ptr< DampingBase > &damping) |
virtual void | setJacobianData (const Matrix6Xd_t &jacobian_data) |
virtual | ~ConstraintSolver () |
Additional Inherited Members | |
![]() | |
std::set< ConstraintBase_t > | constraints_ |
set inserts sorted (default less operator); if element has already been added it returns an iterator on it. More... | |
boost::shared_ptr< DampingBase > | damping_ |
References the current Jacobian (matrix data only). More... | |
Matrix6Xd_t | jacobian_data_ |
References the limiter parameters (up-to-date according to KinematicExtension). More... | |
const LimiterParams & | limiter_params_ |
References the inv. diff. kin. solver parameters. More... | |
const TwistControllerParams & | params_ |
Set of constraints. More... | |
PInvBySVD | pinv_calc_ |
The currently set damping method. More... | |
TaskStackController_t & | task_stack_controller_ |
An instance that helps solving the inverse of the Jacobian. More... | |
Definition at line 30 of file gradient_projection_method_solver.h.
|
inline |
Definition at line 33 of file gradient_projection_method_solver.h.
|
inlinevirtual |
Definition at line 39 of file gradient_projection_method_solver.h.
|
virtual |
Specific implementation of solve-method to solve IK problem with constraints by using the GPM. See base class ConstraintSolver for more details on params and returns.
Solve the inverse differential kinematics equation by using GPM. In addtion to the partial solution q_dot = J^+ * v the homogeneous solution (I - J^+ * J) q_dot_0 is calculated. The q_dot_0 results from the sum of the constraint cost function gradients. The terms of the sum are weighted with a factor k_H separately.
Implements ConstraintSolver<>.
Definition at line 28 of file gradient_projection_method_solver.cpp.