mc_tasks::SplineTrajectoryTask< Derived > Struct Template Reference

Generic CRTP implementation for a task tracking a curve in both position and orientation. This class takes care of much of the logic behind tracking a curve: More...

#include <mc_tasks/SplineTrajectoryTask.h>

Inheritance diagram for mc_tasks::SplineTrajectoryTask< Derived >:
Collaboration diagram for mc_tasks::SplineTrajectoryTask< Derived >:

Public Types

using SplineTrajectoryBase = SplineTrajectoryTask< Derived >
 
using TrajectoryTask = TrajectoryTaskGeneric
 
using SequenceInterpolator6d = mc_trajectory::SequenceInterpolator< Eigen::Vector6d, mc_trajectory::LinearInterpolation< Eigen::Vector6d > >
 
- Public Types inherited from mc_tasks::TrajectoryTaskGeneric
using TrajectoryBase = TrajectoryTaskGeneric
 
- Public Types inherited from mc_tasks::MetaTask
using Backend = mc_solver::QPSolver::Backend
 

Public Member Functions

 SplineTrajectoryTask (const mc_rbdyn::RobotFrame &frame, double duration, double stiffness, double weight, const Eigen::Matrix3d &target, const std::vector< std::pair< double, Eigen::Matrix3d >> &oriWp={})
 Constructor. More...
 
void load (mc_solver::QPSolver &solver, const mc_rtc::Configuration &config) override
 Load parameters from a Configuration object. More...
 
std::function< bool(const mc_tasks::MetaTask &, std::string &)> buildCompletionCriteria (double dt, const mc_rtc::Configuration &config) const override
 
void oriWaypoints (const std::vector< std::pair< double, Eigen::Matrix3d >> &oriWp)
 Sets the orientation waypoints. More...
 
bool timeElapsed () const
 Whether the trajectory has finished. More...
 
Eigen::VectorXd eval () const override
 Returns the transformError between current robot surface pose and its final target. More...
 
virtual Eigen::VectorXd evalTracking () const
 Returns the trajectory tracking error: transformError between the current robot surface pose and its next desired pose along the trajectory error. More...
 
void target (const sva::PTransformd &target)
 Sets the curve target pose. Translation target will be handled by the Derived curve, while orientation target is interpolated here. More...
 
const sva::PTransformd target () const
 Gets the target pose (position/orientation) More...
 
void displaySamples (unsigned s)
 Number of points to sample on the spline for the gui display. More...
 
unsigned displaySamples () const
 Number of samples for displaying the spline. More...
 
void pause (bool paused)
 Allows to pause the task. More...
 
bool pause () const noexcept
 
double currentTime () const noexcept
 
double duration () const noexcept
 Returns the trajectory's duration. More...
 
Setters for the tasks gains and gain interpolation (dimWeight/Stiffnes/Damping)

This task supports two different ways to define gains:

If an interpolation method is present, calling the corresponding dimWeight/stiffness/damping/setGains setter will disable interpolation and set a constant gain. The interpolation setters ensure that gains are interpolated starting from the current (time, gain) values.

void dimWeight (const Eigen::VectorXd &dimW) override
 Sets the dimensional weights (controls the importance of orientation/translation). More...
 
Eigen::VectorXd dimWeight () const override
 Gets the dimensional weights (orientation/translation) 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...
 
void dimWeightInterpolation (const std::vector< std::pair< double, Eigen::Vector6d >> &dimWeights)
 
const std::vector< std::pair< double, Eigen::Vector6d > > & dimWeightInterpolation () const noexcept
 Sets the dimensional weights (controls the importance of orientation/translation). More...
 
void stiffnessInterpolation (const std::vector< std::pair< double, Eigen::Vector6d >> &stiffnessGains)
 
const std::vector< std::pair< double, Eigen::Vector6d > > & stiffnessInterpolation () const noexcept
 Sets the dimensional weights (controls the importance of orientation/translation). More...
 
void dampingInterpolation (const std::vector< std::pair< double, Eigen::Vector6d >> &dampingGains)
 
const std::vector< std::pair< double, Eigen::Vector6d > > & dampingInterpolation () const noexcept
 Sets the dimensional weights (controls the importance of orientation/translation). 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 dimWeight (const Eigen::VectorXd &dimW) override
 Sets the dimensional weights (controls the importance of orientation/translation). More...
 
Eigen::VectorXd dimWeight () const override
 Sets the dimensional weights (controls the importance of orientation/translation). 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 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
 

Protected Member Functions

void refPose (const sva::PTransformd &pose)
 Tracks a reference world pose. More...
 
const sva::PTransformd & refPose () const
 Returns the trajectory reference world pose. More...
 
void addToGUI (mc_rtc::gui::StateBuilder &gui) override
 Add task controls to the GUI. Interactive controls for the trajectory waypoints and end-endpoints automatically updates the curve. More...
 
void addToLogger (mc_rtc::Logger &logger) override
 Add information about the task to the logger. More...
 
void update (mc_solver::QPSolver &) override
 Update trajectory target. More...
 
void interpolateGains ()
 
void refAccel (const Eigen::VectorXd &accel)
 Set the trajectory reference acceleration. More...
 
const Eigen::VectorXd & refAccel () const
 Get the trajectory reference acceleration. More...
 
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 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 &)
 

Protected Attributes

mc_rbdyn::ConstRobotFramePtr frame_
 
double duration_ = 0
 
mc_trajectory::InterpolatedRotation oriSpline_
 
SequenceInterpolator6d dimWeightInterpolator_
 
SequenceInterpolator6d stiffnessInterpolator_
 
SequenceInterpolator6d dampingInterpolator_
 
bool paused_ = false
 
double currTime_ = 0.
 
unsigned samples_ = 20
 
bool inSolver_ = false
 
- 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
 

Additional Inherited Members

- 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)
 

Detailed Description

template<typename Derived>
struct mc_tasks::SplineTrajectoryTask< Derived >

Generic CRTP implementation for a task tracking a curve in both position and orientation. This class takes care of much of the logic behind tracking a curve:

  • Interpolates between orientation waypoints defined as pairs [time, orientation]
  • Provides reference position/velocity/acceleration from underlying curve (defined in the Derived class)
  • Implements GUI elements for controlling waypoints, targets, etc.
  • Brings in all the functionalities from TrajectoryTaskGeneric

To implement tracking of a new curve, simply derive from this class and implement the functionalites specific to the curve. You need to at least implement:

  • spline() accessors
  • targetPos() accessors/setters The spline itself (as returned by spline()) should at least implement:
  • update() triggers the curve computation if needed (if waypoints/constraints changed)
  • target() accessors/setters
  • splev(t, order) computes the position and its nth-order derivatives at time t along the curve

Member Typedef Documentation

◆ SequenceInterpolator6d

template<typename Derived >
using mc_tasks::SplineTrajectoryTask< Derived >::SequenceInterpolator6d = mc_trajectory::SequenceInterpolator<Eigen::Vector6d, mc_trajectory::LinearInterpolation<Eigen::Vector6d> >

◆ SplineTrajectoryBase

template<typename Derived >
using mc_tasks::SplineTrajectoryTask< Derived >::SplineTrajectoryBase = SplineTrajectoryTask<Derived>

◆ TrajectoryTask

template<typename Derived >
using mc_tasks::SplineTrajectoryTask< Derived >::TrajectoryTask = TrajectoryTaskGeneric

Constructor & Destructor Documentation

◆ SplineTrajectoryTask()

template<typename Derived >
mc_tasks::SplineTrajectoryTask< Derived >::SplineTrajectoryTask ( const mc_rbdyn::RobotFrame frame,
double  duration,
double  stiffness,
double  weight,
const Eigen::Matrix3d &  target,
const std::vector< std::pair< double, Eigen::Matrix3d >> &  oriWp = {} 
)

Constructor.

Parameters
frameControl frame
durationLength of the motion
stiffnessTask stiffness
weightTask weight
targetTarget orientation
oriWpOptional orientation waypoints (pairs of [time, orientation])

Member Function Documentation

◆ addToGUI()

template<typename Derived >
void mc_tasks::SplineTrajectoryTask< Derived >::addToGUI ( mc_rtc::gui::StateBuilder gui)
overrideprotectedvirtual

Add task controls to the GUI. Interactive controls for the trajectory waypoints and end-endpoints automatically updates the curve.

Reimplemented from mc_tasks::MetaTask.

◆ addToLogger()

template<typename Derived >
void mc_tasks::SplineTrajectoryTask< Derived >::addToLogger ( mc_rtc::Logger logger)
overrideprotectedvirtual

Add information about the task to the logger.

Parameters
logger

Reimplemented from mc_tasks::MetaTask.

◆ buildCompletionCriteria()

template<typename Derived >
std::function<bool(const mc_tasks::MetaTask &, std::string &)> mc_tasks::SplineTrajectoryTask< Derived >::buildCompletionCriteria ( double  dt,
const mc_rtc::Configuration config 
) const
overridevirtual

Add support for the following entries

  • timeElapsed: True when the task duration has elapsed
  • wrench: True when the force applied on the robot surface is higher than the provided threshold (6d vector, NaN value ignores the reading, negative values invert the condition). Ignored if the surface has no force-sensor attached.
    Exceptions
    ifthe surface does not have an associated force sensor

Reimplemented from mc_tasks::MetaTask.

◆ currentTime()

template<typename Derived >
double mc_tasks::SplineTrajectoryTask< Derived >::currentTime ( ) const
inlinenoexcept

Returns the current time along the trajectory

◆ damping() [1/5]

template<typename Derived >
double mc_tasks::TrajectoryTaskGeneric::damping

Get the current task damping.

◆ damping() [2/5]

template<typename Derived >
void mc_tasks::TrajectoryTaskGeneric::damping

Set dimensional damping.

The caller should be sure that the dimension of the vector fits the task dimension.

Parameters
dampingDimensional damping

◆ damping() [3/5]

template<typename Derived >
void mc_tasks::SplineTrajectoryTask< Derived >::damping ( const Eigen::VectorXd &  damping)

Set dimensional damping.

The caller should be sure that the dimension of the vector fits the task dimension.

Note
Removes the dampingInterpolator_ if it exists
Parameters
dampingDimensional damping

◆ damping() [4/5]

template<typename Derived >
void mc_tasks::TrajectoryTaskGeneric::damping

Set the task damping, leaving its stiffness unchanged.

Parameters
dampingTask stiffness

◆ damping() [5/5]

template<typename Derived >
void mc_tasks::SplineTrajectoryTask< Derived >::damping ( double  damping)

Set the task damping, leaving its stiffness unchanged.

Note
Removes the dampingInterpolator_ if it exists
Parameters
dampingTask stiffness

◆ dampingInterpolation() [1/2]

template<typename Derived >
const std::vector<std::pair<double, Eigen::Vector6d> >& mc_tasks::SplineTrajectoryTask< Derived >::dampingInterpolation ( ) const
inlinenoexcept

Sets the dimensional weights (controls the importance of orientation/translation).

Note
Removes the dimWeightInterpolator_ if it exists
Exceptions
ifdimW is not a Vector6d
Parameters
dimWWeights expressed as a Vector6d [wx, wy, wz, tx, ty, tz]

◆ dampingInterpolation() [2/2]

template<typename Derived >
void mc_tasks::SplineTrajectoryTask< Derived >::dampingInterpolation ( const std::vector< std::pair< double, Eigen::Vector6d >> &  dampingGains)

Interpolate the dimensional damping between the provided values

Parameters
dampingGainsPairs of [time, dimensional gain]. Must be strictly ordered by ascending time, and time > currentTime()
Note
To remove interpolation, call one of the damping setters (see damping)
If you call this function after the task is started, and wish to keep the gains continuous, you should insert the [currentTime(), dimWeight()] pair in the dampingGains argument.
Exceptions
std::runtime_errorIf dampingGains is not meeting the requirements

◆ dimWeight() [1/4]

template<typename Derived >
Eigen::VectorXd mc_tasks::TrajectoryTaskGeneric::dimWeight
override

Sets the dimensional weights (controls the importance of orientation/translation).

Note
Removes the dimWeightInterpolator_ if it exists
Exceptions
ifdimW is not a Vector6d
Parameters
dimWWeights expressed as a Vector6d [wx, wy, wz, tx, ty, tz]

◆ dimWeight() [2/4]

template<typename Derived >
Eigen::VectorXd mc_tasks::SplineTrajectoryTask< Derived >::dimWeight ( ) const
overridevirtual

Gets the dimensional weights (orientation/translation)

Returns
Dimensional weights expressed as a Vector6d [wx, wy, wz, tx, ty, tz]

Implements mc_tasks::MetaTask.

◆ dimWeight() [3/4]

template<typename Derived >
void mc_tasks::TrajectoryTaskGeneric::dimWeight
override

Sets the dimensional weights (controls the importance of orientation/translation).

Note
Removes the dimWeightInterpolator_ if it exists
Exceptions
ifdimW is not a Vector6d
Parameters
dimWWeights expressed as a Vector6d [wx, wy, wz, tx, ty, tz]

◆ dimWeight() [4/4]

template<typename Derived >
void mc_tasks::SplineTrajectoryTask< Derived >::dimWeight ( const Eigen::VectorXd &  dimW)
overridevirtual

Sets the dimensional weights (controls the importance of orientation/translation).

Note
Removes the dimWeightInterpolator_ if it exists
Exceptions
ifdimW is not a Vector6d
Parameters
dimWWeights expressed as a Vector6d [wx, wy, wz, tx, ty, tz]

Implements mc_tasks::MetaTask.

◆ dimWeightInterpolation() [1/2]

template<typename Derived >
const std::vector<std::pair<double, Eigen::Vector6d> >& mc_tasks::SplineTrajectoryTask< Derived >::dimWeightInterpolation ( ) const
inlinenoexcept

Sets the dimensional weights (controls the importance of orientation/translation).

Note
Removes the dimWeightInterpolator_ if it exists
Exceptions
ifdimW is not a Vector6d
Parameters
dimWWeights expressed as a Vector6d [wx, wy, wz, tx, ty, tz]

◆ dimWeightInterpolation() [2/2]

template<typename Derived >
void mc_tasks::SplineTrajectoryTask< Derived >::dimWeightInterpolation ( const std::vector< std::pair< double, Eigen::Vector6d >> &  dimWeights)

Interpolate the dimensional weight between the specified values

Parameters
dimWeightsPairs of [time, dimensional gain], strictly ordered by ascending time.
Note
To remove interpolation, call dimWeight
If you call this function after the task is started, and wish to keep the gains continuous, you should insert the [currentTime(), dimWeight()] pair in the dimWeights argument.
Exceptions
std::runtime_errorIf dimWeights is not meeting the requirements

◆ displaySamples() [1/2]

template<typename Derived >
unsigned mc_tasks::SplineTrajectoryTask< Derived >::displaySamples ( ) const

Number of samples for displaying the spline.

Returns
number of samples

◆ displaySamples() [2/2]

template<typename Derived >
void mc_tasks::SplineTrajectoryTask< Derived >::displaySamples ( unsigned  s)

Number of points to sample on the spline for the gui display.

Parameters
snumber of samples

◆ duration()

template<typename Derived >
double mc_tasks::SplineTrajectoryTask< Derived >::duration ( ) const
inlinenoexcept

Returns the trajectory's duration.

◆ eval()

template<typename Derived >
Eigen::VectorXd mc_tasks::SplineTrajectoryTask< Derived >::eval ( ) const
overridevirtual

Returns the transformError between current robot surface pose and its final target.

Returns
The error w.r.t the final target

Implements mc_tasks::MetaTask.

◆ evalTracking()

template<typename Derived >
virtual Eigen::VectorXd mc_tasks::SplineTrajectoryTask< Derived >::evalTracking ( ) const
virtual

Returns the trajectory tracking error: transformError between the current robot surface pose and its next desired pose along the trajectory error.

Returns
The trajectory tracking error

◆ interpolateGains()

template<typename Derived >
void mc_tasks::SplineTrajectoryTask< Derived >::interpolateGains ( )
protected

Interpolate dimWeight, stiffness, damping

◆ load()

template<typename Derived >
void mc_tasks::SplineTrajectoryTask< Derived >::load ( mc_solver::QPSolver solver,
const mc_rtc::Configuration config 
)
overridevirtual

Load parameters from a Configuration object.

Reimplemented from mc_tasks::MetaTask.

◆ oriWaypoints()

template<typename Derived >
void mc_tasks::SplineTrajectoryTask< Derived >::oriWaypoints ( const std::vector< std::pair< double, Eigen::Matrix3d >> &  oriWp)

Sets the orientation waypoints.

Parameters
oriWpOrientation waypoints defined as pairs of [time, orientation]

◆ pause() [1/2]

template<typename Derived >
bool mc_tasks::SplineTrajectoryTask< Derived >::pause ( ) const
inlinenoexcept

True when the task is paused

◆ pause() [2/2]

template<typename Derived >
void mc_tasks::SplineTrajectoryTask< Derived >::pause ( bool  paused)
inline

Allows to pause the task.

This feature is mainly intended to allow starting the task in paused state to allow adjusting the parameters of the trajectory before its execution. Use with care in other contexts.

Warning
Pausing sets the task's desired velocity and acceleration to zero, which will suddently stop the motion. Unpausing causes the motion to resume at the current speed along the trajectory. Avoid pausing/resuming during high-speed trajectories.
Parameters
pausedTrue to pause the task, False to resume.

◆ refAccel() [1/2]

template<typename Derived >
const Eigen::VectorXd& mc_tasks::TrajectoryTaskGeneric::refAccel
protected

Get the trajectory reference acceleration.

◆ refAccel() [2/2]

template<typename Derived >
void mc_tasks::TrajectoryTaskGeneric::refAccel
protected

Set the trajectory reference acceleration.

Parameters
accelNew reference acceleration

◆ refPose() [1/2]

template<typename Derived >
const sva::PTransformd& mc_tasks::SplineTrajectoryTask< Derived >::refPose ( ) const
protected

Returns the trajectory reference world pose.

Returns
Desired pose (world)

◆ refPose() [2/2]

template<typename Derived >
void mc_tasks::SplineTrajectoryTask< Derived >::refPose ( const sva::PTransformd &  pose)
protected

Tracks a reference world pose.

Parameters
poseDesired position (world)

◆ refVel() [1/2]

template<typename Derived >
const Eigen::VectorXd& mc_tasks::TrajectoryTaskGeneric::refVel
protected

Get the trajectory reference velocity.

◆ refVel() [2/2]

template<typename Derived >
void mc_tasks::TrajectoryTaskGeneric::refVel
protected

Set the trajectory reference velocity.

Parameters
velNew reference velocity

◆ setGains() [1/2]

template<typename Derived >
void mc_tasks::SplineTrajectoryTask< Derived >::setGains ( const Eigen::VectorXd &  stiffness,
const Eigen::VectorXd &  damping 
)

Set dimensional stiffness and damping.

The caller should be sure that the dimensions of the vectors fit the task dimension.

Note
Removes the stiffnessInterpolator_ and dampingInterpolator_ if they exist
Parameters
stiffnessDimensional stiffness
dampingDimensional damping

◆ setGains() [2/2]

template<typename Derived >
void mc_tasks::SplineTrajectoryTask< Derived >::setGains ( double  stiffness,
double  damping 
)

Set both stiffness and damping.

Parameters
stiffnessTask stiffness
Note
Removes the stiffnessInterpolator_ and dampingInterpolator_ if they exist
Parameters
dampingTask damping

◆ stiffness() [1/5]

template<typename Derived >
double mc_tasks::TrajectoryTaskGeneric::stiffness

Get the current task stiffness.

◆ stiffness() [2/5]

template<typename Derived >
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)

Parameters
stiffnessDimensional stiffness

◆ stiffness() [3/5]

template<typename Derived >
void mc_tasks::SplineTrajectoryTask< Derived >::stiffness ( const Eigen::VectorXd &  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)

Note
Removes the stiffnessInterpolator_ if it exists
Parameters
stiffnessDimensional stiffness

◆ stiffness() [4/5]

template<typename Derived >
void mc_tasks::TrajectoryTaskGeneric::stiffness

Set the task stiffness/damping.

Damping is automatically set to 2*sqrt(stiffness)

Parameters
stiffnessTask stiffness

◆ stiffness() [5/5]

template<typename Derived >
void mc_tasks::SplineTrajectoryTask< Derived >::stiffness ( double  stiffness)

Set the task stiffness/damping.

Damping is automatically set to 2*sqrt(stiffness)

Note
Removes the stiffnessInterpolator_ if it exists
Parameters
stiffnessTask stiffness

◆ stiffnessInterpolation() [1/2]

template<typename Derived >
const std::vector<std::pair<double, Eigen::Vector6d> >& mc_tasks::SplineTrajectoryTask< Derived >::stiffnessInterpolation ( ) const
inlinenoexcept

Sets the dimensional weights (controls the importance of orientation/translation).

Note
Removes the dimWeightInterpolator_ if it exists
Exceptions
ifdimW is not a Vector6d
Parameters
dimWWeights expressed as a Vector6d [wx, wy, wz, tx, ty, tz]

◆ stiffnessInterpolation() [2/2]

template<typename Derived >
void mc_tasks::SplineTrajectoryTask< Derived >::stiffnessInterpolation ( const std::vector< std::pair< double, Eigen::Vector6d >> &  stiffnessGains)

Interpolate the stiffness between the provided values

Parameters
stiffnessGainsPairs of [time, dimensional gain], strictly ordered by ascending time.
Note
If there is no dampingInterpolation, damping will be set to 2*sqrt(stiffness)
To remove interpolation, call one of the stiffness setters (see stiffness)
If you call this function after the task is started, and wish to keep the gains continuous, you should insert the [currentTime(), dimWeight()] pair in the stiffnessGains argument.
Exceptions
std::runtime_errorIf stiffnessGains is not meeting the requirements

◆ target() [1/2]

template<typename Derived >
const sva::PTransformd mc_tasks::SplineTrajectoryTask< Derived >::target ( ) const

Gets the target pose (position/orientation)

Returns
target pose

◆ target() [2/2]

template<typename Derived >
void mc_tasks::SplineTrajectoryTask< Derived >::target ( const sva::PTransformd &  target)

Sets the curve target pose. Translation target will be handled by the Derived curve, while orientation target is interpolated here.

Parameters
targetTarget pose for the curve

◆ timeElapsed()

template<typename Derived >
bool mc_tasks::SplineTrajectoryTask< Derived >::timeElapsed ( ) const

Whether the trajectory has finished.

Returns
True if the trajectory has finished

◆ update()

template<typename Derived >
void mc_tasks::SplineTrajectoryTask< Derived >::update ( mc_solver::QPSolver )
overrideprotectedvirtual

Update trajectory target.

Implements mc_tasks::MetaTask.

Member Data Documentation

◆ currTime_

template<typename Derived >
double mc_tasks::SplineTrajectoryTask< Derived >::currTime_ = 0.
protected

◆ dampingInterpolator_

template<typename Derived >
SequenceInterpolator6d mc_tasks::SplineTrajectoryTask< Derived >::dampingInterpolator_
protected

◆ dimWeightInterpolator_

template<typename Derived >
SequenceInterpolator6d mc_tasks::SplineTrajectoryTask< Derived >::dimWeightInterpolator_
protected

◆ duration_

template<typename Derived >
double mc_tasks::SplineTrajectoryTask< Derived >::duration_ = 0
protected

◆ frame_

template<typename Derived >
mc_rbdyn::ConstRobotFramePtr mc_tasks::SplineTrajectoryTask< Derived >::frame_
protected

◆ inSolver_

template<typename Derived >
bool mc_tasks::SplineTrajectoryTask< Derived >::inSolver_ = false
protected

◆ oriSpline_

template<typename Derived >
mc_trajectory::InterpolatedRotation mc_tasks::SplineTrajectoryTask< Derived >::oriSpline_
protected

◆ paused_

template<typename Derived >
bool mc_tasks::SplineTrajectoryTask< Derived >::paused_ = false
protected

◆ samples_

template<typename Derived >
unsigned mc_tasks::SplineTrajectoryTask< Derived >::samples_ = 20
protected

◆ stiffnessInterpolator_

template<typename Derived >
SequenceInterpolator6d mc_tasks::SplineTrajectoryTask< Derived >::stiffnessInterpolator_
protected

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