mc_tasks::OrientationTask Struct Reference

Control the orientation of a frame. More...

#include <mc_tasks/OrientationTask.h>

Inheritance diagram for mc_tasks::OrientationTask:
Collaboration diagram for mc_tasks::OrientationTask:

Public Member Functions

 OrientationTask (const mc_rbdyn::RobotFrame &frame, double stiffness=2.0, double weight=500.0)
 Constructor. More...
 
 OrientationTask (const std::string &bodyName, const mc_rbdyn::Robots &robots, unsigned int robotIndex, double stiffness=2.0, double weight=500)
 Constructor. More...
 
void reset () override
 Reset the task. More...
 
void orientation (const Eigen::Matrix3d &ori)
 Set the frame orientation target. More...
 
Eigen::Matrix3d orientation ()
 Get the current frame orientation target. More...
 
void addToLogger (mc_rtc::Logger &logger) override
 
- Public Member Functions inherited from mc_tasks::TrajectoryTaskGeneric
 TrajectoryTaskGeneric (const mc_rbdyn::Robots &robots, unsigned int robotIndex, double stiffness, double weight)
 Constructor (auto damping) More...
 
 TrajectoryTaskGeneric (const mc_rbdyn::RobotFrame &frame, double stiffness, double weight)
 Constructor (auto damping) More...
 
virtual ~TrajectoryTaskGeneric ()=default
 
void reset () override
 Reset task target velocity and acceleration to zero. More...
 
void refVel (const Eigen::VectorXd &vel)
 Set the trajectory reference velocity. More...
 
const Eigen::VectorXd & refVel () const
 Get the trajectory reference velocity. More...
 
void refAccel (const Eigen::VectorXd &accel)
 Set the trajectory reference acceleration. More...
 
const Eigen::VectorXd & refAccel () const
 Get the trajectory reference acceleration. More...
 
void stiffness (double stiffness)
 Set the task stiffness/damping. More...
 
void stiffness (const Eigen::VectorXd &stiffness)
 Set dimensional stiffness. More...
 
void damping (double damping)
 Set the task damping, leaving its stiffness unchanged. More...
 
void damping (const Eigen::VectorXd &damping)
 Set dimensional damping. More...
 
void setGains (double stiffness, double damping)
 Set both stiffness and damping. More...
 
void setGains (const Eigen::VectorXd &stiffness, const Eigen::VectorXd &damping)
 Set dimensional stiffness and damping. More...
 
double stiffness () const
 Get the current task stiffness. More...
 
double damping () const
 Get the current task damping. More...
 
const Eigen::VectorXd & dimStiffness () const
 Get the current task dimensional stiffness. More...
 
const Eigen::VectorXd & dimDamping () const
 Get the current task dimensional damping. More...
 
void weight (double w)
 Set the task weight. More...
 
double weight () const
 Returns the task weight. More...
 
void dimWeight (const Eigen::VectorXd &dimW) override
 Set the task's dimension weight vector. More...
 
Eigen::VectorXd dimWeight () const override
 Get the current task's dim weight vector. More...
 
void selectActiveJoints (const std::vector< std::string > &activeJointsName, const std::map< std::string, std::vector< std::array< int, 2 >>> &activeDofs={}, bool checkJoints=true)
 Create an active joints selector. More...
 
void selectActiveJoints (mc_solver::QPSolver &solver, const std::vector< std::string > &activeJointsName, const std::map< std::string, std::vector< std::array< int, 2 >>> &activeDofs={}) override
 Create an active joints selector. More...
 
void selectUnactiveJoints (const std::vector< std::string > &unactiveJointsName, const std::map< std::string, std::vector< std::array< int, 2 >>> &unactiveDofs={}, bool checkJoints=true)
 Create an unactive joints selector. More...
 
void selectUnactiveJoints (mc_solver::QPSolver &solver, const std::vector< std::string > &unactiveJointsName, const std::map< std::string, std::vector< std::array< int, 2 >>> &unactiveDofs={}) override
 Create an unactive joints selector. More...
 
virtual void resetJointsSelector ()
 
void resetJointsSelector (mc_solver::QPSolver &solver) override
 Reset active joints selection. More...
 
Eigen::VectorXd eval () const override
 Returns the task error. More...
 
Eigen::VectorXd speed () const override
 Returns the task velocity. More...
 
const Eigen::VectorXd & normalAcc () const
 
void load (mc_solver::QPSolver &solver, const mc_rtc::Configuration &config) override
 Load parameters from a Configuration object. More...
 
- Public Member Functions inherited from mc_tasks::MetaTask
 MetaTask ()
 
virtual ~MetaTask ()
 
const std::string & type () const
 
virtual void name (const std::string &name)
 
const std::string & name () const
 
size_t iterInSolver () const noexcept
 Get the number of iterations since the task was added to the solver. More...
 
void resetIterInSolver () noexcept
 Set the number of iterations since the task was added to the solver to zero. More...
 
void incrementIterInSolver () noexcept
 Increment the number of iterations since the task was added to the solver. More...
 
Backend backend () const noexcept
 

Public Attributes

mc_rbdyn::ConstRobotFramePtr frame_
 

Protected Member Functions

void addToGUI (mc_rtc::gui::StateBuilder &gui) override
 
- Protected Member Functions inherited from mc_tasks::TrajectoryTaskGeneric
template<Backend backend, typename ErrorT , typename... Args>
void finalize (Args &&... args)
 
void addToGUI (mc_rtc::gui::StateBuilder &) override
 
void addToLogger (mc_rtc::Logger &logger) override
 
std::function< bool(const mc_tasks::MetaTask &task, std::string &)> buildCompletionCriteria (double dt, const mc_rtc::Configuration &config) const override
 
void addToSolver (mc_solver::QPSolver &solver) override
 Add the task to a solver. More...
 
void removeFromSolver (mc_solver::QPSolver &solver) override
 Remove the task from a solver. More...
 
void update (mc_solver::QPSolver &) override
 Update the task. More...
 
- Protected Member Functions inherited from mc_tasks::MetaTask
virtual void removeFromLogger (mc_rtc::Logger &)
 
virtual void removeFromGUI (mc_rtc::gui::StateBuilder &)
 

Friends

struct EndEffectorTask
 

Additional Inherited Members

- Public Types inherited from mc_tasks::TrajectoryTaskGeneric
using TrajectoryBase = TrajectoryTaskGeneric
 
- Public Types inherited from mc_tasks::MetaTask
using Backend = mc_solver::QPSolver::Backend
 
- Static Protected Member Functions inherited from mc_tasks::MetaTask
static void addToSolver (MetaTask &t, mc_solver::QPSolver &solver)
 
static void removeFromSolver (MetaTask &t, mc_solver::QPSolver &solver)
 
static void update (MetaTask &t, mc_solver::QPSolver &solver)
 
static void addToLogger (MetaTask &t, mc_rtc::Logger &logger)
 
static void removeFromLogger (MetaTask &t, mc_rtc::Logger &logger)
 
static void addToGUI (MetaTask &t, mc_rtc::gui::StateBuilder &gui)
 
static void removeFromGUI (MetaTask &t, mc_rtc::gui::StateBuilder &gui)
 
static void ensureHasJoints (const mc_rbdyn::Robot &robot, const std::vector< std::string > &joints, const std::string &prefix)
 
- Protected Attributes inherited from mc_tasks::TrajectoryTaskGeneric
const mc_rbdyn::Robotsrobots
 
unsigned int rIndex
 
mc_rtc::void_ptr errorT {nullptr, nullptr}
 
Eigen::VectorXd refVel_
 
Eigen::VectorXd refAccel_
 
bool inSolver_ = false
 
mc_rtc::void_ptr trajectoryT_ {nullptr, nullptr}
 
Eigen::VectorXd stiffness_
 
Eigen::VectorXd damping_
 
double weight_
 
mc_rtc::void_ptr selectorT_ {nullptr, nullptr}
 
- Protected Attributes inherited from mc_tasks::MetaTask
Backend backend_
 
std::string type_
 
std::string name_
 
size_t iterInSolver_ = 0
 

Detailed Description

Control the orientation of a frame.

Constructor & Destructor Documentation

◆ OrientationTask() [1/2]

mc_tasks::OrientationTask::OrientationTask ( const mc_rbdyn::RobotFrame frame,
double  stiffness = 2.0,
double  weight = 500.0 
)

Constructor.

Parameters
frameControl frame
stiffnessTask stiffness
weightTask weight

◆ OrientationTask() [2/2]

mc_tasks::OrientationTask::OrientationTask ( const std::string &  bodyName,
const mc_rbdyn::Robots robots,
unsigned int  robotIndex,
double  stiffness = 2.0,
double  weight = 500 
)

Constructor.

Parameters
bodyNameName of the body to control
robotsRobots controlled by this task
robotIndexIndex of the robot controlled by this task
stiffnessTask stiffness
weightTask weight

Member Function Documentation

◆ addToGUI()

void mc_tasks::OrientationTask::addToGUI ( mc_rtc::gui::StateBuilder )
overrideprotectedvirtual

Add elements to the GUI through the helper

This will be called by the solver when the task is added.

The default implementation adds the type of the task under the {"Tasks", name_} category.

Reimplemented from mc_tasks::MetaTask.

◆ addToLogger()

void mc_tasks::OrientationTask::addToLogger ( mc_rtc::Logger )
overridevirtual

Add entries to the logger

This will be called by the solver if it holds a valid logger instance when the task is added.

The default implementation adds nothing to the log.

Reimplemented from mc_tasks::MetaTask.

◆ orientation() [1/2]

Eigen::Matrix3d mc_tasks::OrientationTask::orientation ( )

Get the current frame orientation target.

Returns
The body orientation target in world frame

◆ orientation() [2/2]

void mc_tasks::OrientationTask::orientation ( const Eigen::Matrix3d &  ori)

Set the frame orientation target.

Parameters
oriBody orientation in world frame

◆ reset()

void mc_tasks::OrientationTask::reset ( )
overridevirtual

Reset the task.

Set the task objective to the current frame orientation

Implements mc_tasks::MetaTask.

Friends And Related Function Documentation

◆ EndEffectorTask

friend struct EndEffectorTask
friend

Member Data Documentation

◆ frame_

mc_rbdyn::ConstRobotFramePtr mc_tasks::OrientationTask::frame_

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