Class Gaze

Inheritance Relationships

Base Type

Class Documentation

class Gaze : public OpenSoT::Task<Eigen::MatrixXd, Eigen::VectorXd>

The Gaze class implement a Cartesian Task in which is controlled the gaze of the robot.

The algorithm used is based on the paper: “Adaptive Predictive Gaze Control of a Redundant Humanoid

Robot Head, IROS2011”. Notice that the controlled distal link is always “gaze” in a certain base_link set by the user.

Public Types

typedef std::shared_ptr<Gaze> Ptr

Public Functions

Gaze(std::string task_id, XBot::ModelInterface &robot, std::string base_link, std::string distal_link = "gaze")
~Gaze()
void setGaze(const Eigen::Affine3d &desiredGaze)

setGaze

Parameters

desiredGaze – pose of the object to observe in base_link

void setGaze(const Eigen::MatrixXd &desiredGaze)
void setGaze(const KDL::Frame &desiredGaze)
void setOrientationErrorGain(const double &orientationErrorGain)
const double getOrientationErrorGain() const
virtual void setWeight(const Eigen::MatrixXd &W)

setWeight sets the task weight.

Note the Weight needs to be positive definite. If your original intent was to get a subtask (i.e., reduce the number of rows of the task Jacobian), please use the class SubTask

Parameters

W – matrix weight

virtual std::list<ConstraintPtr> &getConstraints()

getConstraints return a reference to the constraint list.

Use the standard list methods to add, remove, clear, … the constraints list. e.g.: task.getConstraints().push_back(new_constraint) Notice that in subtasks, you will get the constraint list of the father Task from which the SubTask is generated.

Returns

the list of constraints to which the father Task is subject.

virtual const unsigned int getTaskSize() const

Gets the task size.

Returns

the number of rows of A

virtual std::vector<bool> getActiveJointsMask()

getActiveJointsMask return a vector of length NumberOfDOFs.

If an element is false the corresponding column of the task jacobian is set to 0.

Returns

a vector of bool

virtual bool setActiveJointsMask(const std::vector<bool> &active_joints_mask)

setActiveJointsMask set a mask on the jacobian

Parameters

active_joints_mask

Returns

true if success

inline std::string getDistalLink()

getDistalLink return “gaze” as controlled link

Returns

string with distal link name

virtual void setLambda(double lambda)

getLambda

Returns

the lambda weight of the task

bool setBaseLink(const std::string &base_link)

setBaseLink change the base link of the task

Parameters

base_link – the new base link

Returns

false if the base link does not exists