Public Member Functions | Protected Attributes | List of all members
TaskPrioritySolver Class Reference

#include <task_priority_solver.h>

Inheritance diagram for TaskPrioritySolver:
Inheritance graph
[legend]

Public Member Functions

virtual Eigen::MatrixXd solve (const Vector6d_t &in_cart_velocities, const JointStates &joint_states)
 
 TaskPrioritySolver (const TwistControllerParams &params, const LimiterParams &limiter_params, TaskStackController_t &task_stack_controller)
 
virtual ~TaskPrioritySolver ()
 
- Public Member Functions inherited from ConstraintSolver<>
void clearConstraints ()
 
 ConstraintSolver (const TwistControllerParams &params, 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 ()
 

Protected Attributes

ros::Time last_time_
 
- Protected Attributes inherited from ConstraintSolver<>
std::set< ConstraintBase_tconstraints_
 set inserts sorted (default less operator); if element has already been added it returns an iterator on it. More...
 
boost::shared_ptr< DampingBasedamping_
 References the current Jacobian (matrix data only). More...
 
Matrix6Xd_t jacobian_data_
 References the limiter parameters (up-to-date according to KinematicExtension). More...
 
const LimiterParamslimiter_params_
 References the inv. diff. kin. solver parameters. More...
 
const TwistControllerParamsparams_
 Set of constraints. More...
 
PInvBySVD pinv_calc_
 The currently set damping method. More...
 
TaskStackController_ttask_stack_controller_
 An instance that helps solving the inverse of the Jacobian. More...
 

Detailed Description

Definition at line 31 of file task_priority_solver.h.

Constructor & Destructor Documentation

◆ TaskPrioritySolver()

TaskPrioritySolver::TaskPrioritySolver ( const TwistControllerParams params,
const LimiterParams limiter_params,
TaskStackController_t task_stack_controller 
)
inline

Definition at line 34 of file task_priority_solver.h.

◆ ~TaskPrioritySolver()

virtual TaskPrioritySolver::~TaskPrioritySolver ( )
inlinevirtual

Definition at line 42 of file task_priority_solver.h.

Member Function Documentation

◆ solve()

Eigen::MatrixXd TaskPrioritySolver::solve ( const Vector6d_t in_cart_velocities,
const JointStates joint_states 
)
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 a two tasks. Maciejewski A., Obstacle Avoidance for Kinematically Redundant Manipulators in Dyn Varying Environments.

Implements ConstraintSolver<>.

Definition at line 26 of file task_priority_solver.cpp.

Member Data Documentation

◆ last_time_

ros::Time TaskPrioritySolver::last_time_
protected

Definition at line 53 of file task_priority_solver.h.


The documentation for this class was generated from the following files:


cob_twist_controller
Author(s): Felix Messmer , Marco Bezzon , Christoph Mark , Francisco Moreno
autogenerated on Mon May 1 2023 02:50:29