RobWorkProject  23.9.11-
Classes | Public Types | Public Member Functions | List of all members
XQPController Class Reference

An extended version of the QPController. More...

#include <XQPController.hpp>

Classes

class  Constraint
 Constraint for the XQPController. More...
 

Public Types

enum  ProjectionFrame { BaseFrame = 0 , ControlFrame }
 Enumeration used to specify frame associated with the projection. More...
 
typedef rw::core::Ptr< XQPControllerPtr
 Definition of smart pointer to XQPController.
 

Public Member Functions

 XQPController (rw::core::Ptr< rw::models::Device > device, rw::core::Ptr< rw::kinematics::Frame > controlFrame, const rw::kinematics::State &state, double dt)
 Constructs XQPController. More...
 
virtual ~XQPController ()
 Destructor.
 
rw::math::Q solve (const rw::math::Q &q, const rw::math::Q &dq, const rw::math::VelocityScrew6D<> &tcpvel, const std::list< Constraint > &constraints)
 Solves the inverse kinematics problem. More...
 
void setProjection (const Eigen::MatrixXd &P, ProjectionFrame space)
 Setup the projection. More...
 
void setAccScale (double scale)
 Sets a scale for the acceleration limits. More...
 
void setVelScale (double scale)
 Sets a scale for the velocity limits. More...
 
void calculateVelocityLimits (Eigen::VectorXd &lower, Eigen::VectorXd &upper, const rw::math::Q &q, const rw::math::Q &dq)
 

Detailed Description

An extended version of the QPController.

Notice: Still under development

The XQPController extends the QPController by providing the user with the possibility of adding constraints on the motion. This method follows the algorithm described in [1].

[1]: Write name of paper when published

Member Enumeration Documentation

◆ ProjectionFrame

Enumeration used to specify frame associated with the projection.

Enumerator
ControlFrame 

Robot Base Frame The Frame specified as the controlFrame

Constructor & Destructor Documentation

◆ XQPController()

XQPController ( rw::core::Ptr< rw::models::Device device,
rw::core::Ptr< rw::kinematics::Frame controlFrame,
const rw::kinematics::State state,
double  dt 
)

Constructs XQPController.

Parameters
device[in] Device to control
controlFrame[in] Frame to control
state[in] State specifying how frames are assempled
dt[in] time step size

Member Function Documentation

◆ calculateVelocityLimits()

void calculateVelocityLimits ( Eigen::VectorXd &  lower,
Eigen::VectorXd &  upper,
const rw::math::Q q,
const rw::math::Q dq 
)

Calculates the velocity limits

◆ setAccScale()

void setAccScale ( double  scale)

Sets a scale for the acceleration limits.

Use this method to scale the acceleration limit e.g. to reduce the power with which it can accelerate.

◆ setProjection()

void setProjection ( const Eigen::MatrixXd &  P,
ProjectionFrame  space 
)

Setup the projection.

The traditional relationship between device Jacobian, joint velocities and tool velocity is given by \(J\dot{q}=\dot{q}\). To ignore certain degrees of freedom or put more emphasis (with respect to the least square solution) on some we can multiply with \(P\) to get \(P J\dot{q}=P \dot{x}\).

\(P\) needs to have exactly 6 columns, however the number of row may be less than 6. Use the space flag to specify in which space the projection should occur.

Usage: Setup to ignore tool roll

XQPController* xqp = new XQPController(device, device->getEnd(), state, dt)
Eigen::MatrixXd P = Eigen::MatrixXd::Zero(5,6);
for (int i = 0; i<5; i++)
P(i,i) = 1;
xqp->setProjection(P, XQPController::ControlFrame);
XQPController(rw::core::Ptr< rw::models::Device > device, rw::core::Ptr< rw::kinematics::Frame > controlFrame, const rw::kinematics::State &state, double dt)
Constructs XQPController.
@ ControlFrame
Definition: XQPController.hpp:112

Usage: Increase the weight of the z-coordinate relative to the base

XQPController* xqp = new XQPController(device, device->getEnd(), state, dt);
Eigen::MatrixXd P = Eigen::MatrixXd::Identity(6,6);
P(2,2) = 100; //Increase the least square weight with a factor of 100
xqp->setProjection(P, XQPController::BaseFrame);
Parameters
P[in] The projection matrix
space[in] The space in which to apply the projection

◆ setVelScale()

void setVelScale ( double  scale)

Sets a scale for the velocity limits.

Use this method to scale the velocity limits e.g. to reduce the speed of the robot

◆ solve()

rw::math::Q solve ( const rw::math::Q q,
const rw::math::Q dq,
const rw::math::VelocityScrew6D<> &  tcpvel,
const std::list< Constraint > &  constraints 
)

Solves the inverse kinematics problem.

Notice that if the constraints cannot be fullfilled, no quarantees for the return value is given.

Parameters
q[in] Current configuration of the device
dq[in] Current joint velocities for the device
tcpvel[in] Desired tool velocity seen in base frame
constraints[in] List of constraints

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