Control a frame 6D pose. More...
#include <mc_tasks/TransformTask.h>
Public Member Functions | |
TransformTask (const mc_rbdyn::RobotFrame &frame, double stiffness=2.0, double weight=500.0) | |
Constructor. More... | |
TransformTask (const std::string &surfaceName, const mc_rbdyn::Robots &robots, unsigned int robotIndex, double stiffness=2.0, double weight=500) | |
Constructor. More... | |
void | reset () override |
Reset the task. More... | |
virtual sva::PTransformd | target () const |
Get the task's target. More... | |
virtual void | target (const sva::PTransformd &worldPos) |
Set the task's target. More... | |
virtual void | targetVel (const sva::MotionVecd &worldVel) |
Get the task's target velocity. More... | |
void | targetSurface (unsigned int robotIndex, const std::string &surfaceName, const sva::PTransformd &offset=sva::PTransformd::Identity()) |
Targets a robot surface with an optional offset. The offset is expressed in the target contact frame. More... | |
void | targetFrame (const mc_rbdyn::Frame &targetFrame, const sva::PTransformd &offset=sva::PTransformd::Identity()) |
Targets a given frame with an optional offset. More... | |
void | targetFrameVelocity (const mc_rbdyn::Frame &targetFrame, const sva::PTransformd &offset=sva::PTransformd::Identity()) |
Targets a given frame velocity with an optional offset. More... | |
virtual void | target (const mc_rbdyn::Frame &frame, const sva::PTransformd &offset) |
Targets a given frame with an optional offset. More... | |
const std::string & | surface () const noexcept |
Retrieve the controlled frame name. More... | |
const mc_rbdyn::RobotFrame & | frame () const noexcept |
Return the controlled frame (const) More... | |
sva::PTransformd | surfacePose () const noexcept |
std::function< bool(const mc_tasks::MetaTask &task, std::string &)> | buildCompletionCriteria (double dt, const mc_rtc::Configuration &config) const override |
void | addToLogger (mc_rtc::Logger &logger) override |
void | setGains (const sva::MotionVecd &stiffness, const sva::MotionVecd &damping) |
Set dimensional stiffness and damping. More... | |
void | stiffness (const sva::MotionVecd &stiffness) |
Set dimensional stiffness. More... | |
sva::MotionVecd | mvStiffness () |
Get dimensional stiffness as a motion vector. More... | |
void | damping (const sva::MotionVecd &damping) |
Set dimensional damping. More... | |
sva::MotionVecd | mvDamping () |
Get dimensional damping as a motion vector. More... | |
void | refVelB (const sva::MotionVecd &velB) |
Set trajectory task's reference velocity from motion vector in frame coordinates. More... | |
sva::MotionVecd | refVelB () const |
Get reference velocity in frame coordinates as a motion vector. More... | |
void | refAccel (const sva::MotionVecd &accel) |
Set trajectory task's reference acceleration from motion vector. More... | |
void | load (mc_solver::QPSolver &solver, const mc_rtc::Configuration &config) override |
Load parameters from a Configuration object. More... | |
void | damping (double damping) |
Set the task damping, leaving its stiffness unchanged. More... | |
void | damping (const Eigen::VectorXd &damping) |
Set dimensional damping. More... | |
double | damping () const |
Get the current task 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... | |
void | stiffness (double stiffness) |
Set the task stiffness/damping. More... | |
void | stiffness (const Eigen::VectorXd &stiffness) |
Set dimensional stiffness. More... | |
double | stiffness () const |
Get the current task stiffness. More... | |
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 | 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 |
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 |
Protected Member Functions | |
void | addToGUI (mc_rtc::gui::StateBuilder &gui) override |
void | refVel (const Eigen::VectorXd &vel) |
Set the trajectory reference velocity. More... | |
const Eigen::VectorXd & | refVel () const |
Get the trajectory reference velocity. More... | |
Protected Member Functions inherited from mc_tasks::TrajectoryTaskGeneric | |
template<Backend backend, typename ErrorT , typename... Args> | |
void | finalize (Args &&... args) |
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 &) |
Protected Attributes | |
mc_rbdyn::ConstRobotFramePtr | frame_ |
Protected Attributes inherited from mc_tasks::TrajectoryTaskGeneric | |
const mc_rbdyn::Robots & | robots |
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 |
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) |
Control a frame 6D pose.
mc_tasks::TransformTask::TransformTask | ( | const mc_rbdyn::RobotFrame & | frame, |
double | stiffness = 2.0 , |
||
double | weight = 500.0 |
||
) |
Constructor.
frame | Frame controlled by this task |
stiffness | Task stiffness |
weight | Task weight |
mc_tasks::TransformTask::TransformTask | ( | const std::string & | surfaceName, |
const mc_rbdyn::Robots & | robots, | ||
unsigned int | robotIndex, | ||
double | stiffness = 2.0 , |
||
double | weight = 500 |
||
) |
Constructor.
Prefer the frame-based constructor
surfaceName | Name of the surface frame to control |
robots | Robots controlled by this task |
robotIndex | Index of the robot controlled by this task |
stiffness | Task stiffness |
weight | Task weight |
|
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::TrajectoryTaskGeneric.
|
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::TrajectoryTaskGeneric.
|
overridevirtual |
Add support for the following criterias:
If | wrench is used but the surface is not attached to a force sensor |
Reimplemented from mc_tasks::TrajectoryTaskGeneric.
double mc_tasks::TrajectoryTaskGeneric::damping |
Get the current task damping.
void mc_tasks::TrajectoryTaskGeneric::damping |
Set dimensional damping.
The caller should be sure that the dimension of the vector fits the task dimension.
damping | Dimensional damping |
|
inline |
Set dimensional damping.
damping | Dimensional damping as a motion vector |
void mc_tasks::TrajectoryTaskGeneric::damping |
Set the task damping, leaving its stiffness unchanged.
damping | Task stiffness |
|
inlinenoexcept |
Return the controlled frame (const)
|
overridevirtual |
Load parameters from a Configuration object.
Reimplemented from mc_tasks::TrajectoryTaskGeneric.
|
inline |
Get dimensional damping as a motion vector.
|
inline |
Get dimensional stiffness as a motion vector.
|
inline |
Set trajectory task's reference acceleration from motion vector.
acc | Reference acceleration in frame coordinates |
|
protected |
Get the trajectory reference velocity.
|
protected |
Set the trajectory reference velocity.
vel | New reference velocity |
|
inline |
Get reference velocity in frame coordinates as a motion vector.
|
inline |
Set trajectory task's reference velocity from motion vector in frame coordinates.
velB | Reference velocity in frame coordinates |
|
overridevirtual |
Reset the task.
Set the task target to the current frame position
Reset its target velocity and acceleration to zero.
Reimplemented from mc_tasks::TrajectoryTaskGeneric.
void mc_tasks::TrajectoryTaskGeneric::setGains |
Set dimensional stiffness and damping.
The caller should be sure that the dimensions of the vectors fit the task dimension.
stiffness | Dimensional stiffness |
damping | Dimensional damping |
|
inline |
Set dimensional stiffness and damping.
stiffness | Dimensional stiffness |
damping | Dimensional damping |
void mc_tasks::TrajectoryTaskGeneric::setGains |
Set both stiffness and damping.
stiffness | Task stiffness |
damping | Task damping |
double mc_tasks::TrajectoryTaskGeneric::stiffness |
Get the current task stiffness.
void mc_tasks::TrajectoryTaskGeneric::stiffness |
Set dimensional stiffness.
The caller should be sure that the dimension of the vector fits the task dimension.
Damping is automatically set to 2*sqrt(stiffness)
stiffness | Dimensional stiffness |
|
inline |
Set dimensional stiffness.
Damping is automatically set to 2*sqrt(stiffness)
stiffness | Dimensional stiffness as a motion vector |
void mc_tasks::TrajectoryTaskGeneric::stiffness |
Set the task stiffness/damping.
Damping is automatically set to 2*sqrt(stiffness)
stiffness | Task stiffness |
|
inlinenoexcept |
Retrieve the controlled frame name.
|
inlinenoexcept |
Returns the pose of the frame in the inertial frame
|
virtual |
Get the task's target.
|
virtual |
Targets a given frame with an optional offset.
The offset is given in the target frame
targetFrame | Target frame |
offset | Offset relative to targetFrame |
|
virtual |
Set the task's target.
pos | Target in world frame |
void mc_tasks::TransformTask::targetFrame | ( | const mc_rbdyn::Frame & | targetFrame, |
const sva::PTransformd & | offset = sva::PTransformd::Identity() |
||
) |
Targets a given frame with an optional offset.
The offset is given in the target frame
targetFrame | Target frame |
offset | Offset relative to targetFrame |
void mc_tasks::TransformTask::targetFrameVelocity | ( | const mc_rbdyn::Frame & | targetFrame, |
const sva::PTransformd & | offset = sva::PTransformd::Identity() |
||
) |
Targets a given frame velocity with an optional offset.
The offset is given in the target frame
targetFrame | Target frame |
offset | Offset relative to targetFrame |
void mc_tasks::TransformTask::targetSurface | ( | unsigned int | robotIndex, |
const std::string & | surfaceName, | ||
const sva::PTransformd & | offset = sva::PTransformd::Identity() |
||
) |
Targets a robot surface with an optional offset. The offset is expressed in the target contact frame.
robotIndex | Index of the robot to target (could be the environment) |
surfaceName | Surface name in the target robot |
offset | offset defined in the target contact frame |
|
virtual |
Get the task's target velocity.
vel | Target velocity in world frame |
Reimplemented in mc_tasks::force::ImpedanceTask.
|
protected |