Public Member Functions | Private Attributes | List of all members
exotica::Manipulability Class Reference

Manipulability measure. The manipulability measure for a robot at a given joint configuration indicates dexterity, that is, how isotropic the robot's motion is with respect to the task space motion. The measure is high when the manipulator is capable of equal motion in all directions and low when the manipulator is close to a singularity. This task map implements Yoshikawa's manipulability measure

\[ m(x) = \sqrt{J(x)J(x)^T} \]

that is based on the shape of the velocity ellipsoid where $J(x)$ is the manipulator Jacobian matrix.. The task map is expressed by

\[ \phi(x) := -m(x). \]

. More...

#include <manipulability.h>

Inheritance diagram for exotica::Manipulability:
Inheritance graph
[legend]

Public Member Functions

void Instantiate (const ManipulabilityInitializer &init) override
 
int TaskSpaceDim () override
 
void Update (Eigen::VectorXdRefConst x, Eigen::VectorXdRef phi) override
 
- Public Member Functions inherited from exotica::TaskMap
virtual void AssignScene (ScenePtr scene)
 
std::vector< KinematicFrameRequestGetFrames () const
 
virtual std::vector< TaskVectorEntryGetLieGroupIndices ()
 
virtual void InstantiateBase (const Initializer &init)
 
virtual void PreUpdate ()
 
virtual int TaskSpaceJacobianDim ()
 
virtual void Update (Eigen::VectorXdRefConst q, Eigen::VectorXdRef phi, Eigen::MatrixXdRef jacobian)
 
virtual void Update (Eigen::VectorXdRefConst x, Eigen::VectorXdRefConst u, Eigen::VectorXdRef phi, Eigen::MatrixXdRef dphi_dx, Eigen::MatrixXdRef dphi_du)
 
virtual void Update (Eigen::VectorXdRefConst x, Eigen::VectorXdRefConst u, Eigen::VectorXdRef phi)
 
virtual void Update (Eigen::VectorXdRefConst x, Eigen::VectorXdRefConst u, Eigen::VectorXdRef phi, Eigen::MatrixXdRef dphi_dx, Eigen::MatrixXdRef dphi_du, HessianRef ddphi_ddx, HessianRef ddphi_ddu, HessianRef ddphi_dxdu)
 
virtual void Update (Eigen::VectorXdRefConst q, Eigen::VectorXdRef phi, Eigen::MatrixXdRef jacobian, HessianRef hessian)
 
- Public Member Functions inherited from exotica::Object
std::string GetObjectName ()
 
void InstantiateObject (const Initializer &init)
 
 Object ()
 
virtual std::string Print (const std::string &prepend) const
 
virtual std::string type () const
 
virtual ~Object ()
 
- Public Member Functions inherited from exotica::InstantiableBase
 InstantiableBase ()=default
 
virtual ~InstantiableBase ()=default
 
- Public Member Functions inherited from exotica::Instantiable< ManipulabilityInitializer >
std::vector< InitializerGetAllTemplates () const override
 
Initializer GetInitializerTemplate () override
 
const ManipulabilityInitializer & GetParameters () const
 
void InstantiateInternal (const Initializer &init) override
 

Private Attributes

int n_end_effs_
 Number of end-effectors. More...
 
int n_rows_of_jac_
 Number of rows from the top to extract from full jacobian. Is either 3 (position) or 6 (position and rotation). More...
 

Additional Inherited Members

- Public Attributes inherited from exotica::TaskMap
int id
 
bool is_used
 
std::vector< KinematicSolutionkinematics
 
int length
 
int length_jacobian
 
int start
 
int start_jacobian
 
- Public Attributes inherited from exotica::Object
bool debug_
 
std::string ns_
 
std::string object_name_
 
- Protected Attributes inherited from exotica::TaskMap
std::vector< KinematicFrameRequestframes_
 
ScenePtr scene_
 
- Protected Attributes inherited from exotica::Instantiable< ManipulabilityInitializer >
ManipulabilityInitializer parameters_
 

Detailed Description

Manipulability measure. The manipulability measure for a robot at a given joint configuration indicates dexterity, that is, how isotropic the robot's motion is with respect to the task space motion. The measure is high when the manipulator is capable of equal motion in all directions and low when the manipulator is close to a singularity. This task map implements Yoshikawa's manipulability measure

\[ m(x) = \sqrt{J(x)J(x)^T} \]

that is based on the shape of the velocity ellipsoid where $J(x)$ is the manipulator Jacobian matrix.. The task map is expressed by

\[ \phi(x) := -m(x). \]

.

To use the task map as an inequality constraint the lower bound for $\phi$ should be set as a goal and each element should be negative.

Note that

Todo

Definition at line 61 of file manipulability.h.

Member Function Documentation

void exotica::Manipulability::Instantiate ( const ManipulabilityInitializer &  init)
overridevirtual

Reimplemented from exotica::Instantiable< ManipulabilityInitializer >.

Definition at line 47 of file manipulability.cpp.

int exotica::Manipulability::TaskSpaceDim ( )
overridevirtual

Implements exotica::TaskMap.

Definition at line 62 of file manipulability.cpp.

void exotica::Manipulability::Update ( Eigen::VectorXdRefConst  x,
Eigen::VectorXdRef  phi 
)
overridevirtual

Implements exotica::TaskMap.

Definition at line 36 of file manipulability.cpp.

Member Data Documentation

int exotica::Manipulability::n_end_effs_
private

Number of end-effectors.

Definition at line 69 of file manipulability.h.

int exotica::Manipulability::n_rows_of_jac_
private

Number of rows from the top to extract from full jacobian. Is either 3 (position) or 6 (position and rotation).

Definition at line 70 of file manipulability.h.


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


exotica_core_task_maps
Author(s): Yiming Yang, Michael Camilleri
autogenerated on Sat Apr 10 2021 02:36:09