Resurgence (PY2022)
Codebase for the Husky Robotics 2021-2022 rover Resurgence
Loading...
Searching...
No Matches
control::TrapezoidalVelocityProfile< dim > Class Template Reference

Trapezoidal velocity profile in multiple dimensions. More...

#include <TrapezoidalVelocityProfile.h>

Public Member Functions

 TrapezoidalVelocityProfile (double maxVel, double maxAccel)
 Construct a new velocity profile object.
 
void reset ()
 Reset the profile and clear any calculated profile.
 
bool hasTarget () const
 Check if a profile has been calculated.
 
void setTarget (robot::types::datatime_t currTime, const std::array< double, dim > &startPos, const std::array< double, dim > &endPos)
 Calculate a profile, assuming the mechanism begins and ends at rest.
 
void setTarget (robot::types::datatime_t currTime, const navtypes::Vectord< dim > &startPos, const navtypes::Vectord< dim > &endPos)
 Calculate a profile, assuming the mechanism begins and ends at rest.
 
navtypes::Vectord< dim > getCommand (robot::types::datatime_t currTime) const
 Get the target position.
 
std::optional< util::dsecondsgetTotalTime () const
 Get the total time it takes to perform the profile.
 

Detailed Description

template<int dim>
class control::TrapezoidalVelocityProfile< dim >

Trapezoidal velocity profile in multiple dimensions.

Motion is coordinated so that all dimensions arrive at the goal at the same time.

Template Parameters
dimThe number of dimensions that are controlled by this profile.

Constructor & Destructor Documentation

◆ TrapezoidalVelocityProfile()

template<int dim>
control::TrapezoidalVelocityProfile< dim >::TrapezoidalVelocityProfile ( double maxVel,
double maxAccel )
inline

Construct a new velocity profile object.

Parameters
maxVelThe maximum velocity the profile should attain.
maxAccelThe maximum acceleration the profile should use.

Member Function Documentation

◆ getCommand()

template<int dim>
navtypes::Vectord< dim > control::TrapezoidalVelocityProfile< dim >::getCommand ( robot::types::datatime_t currTime) const
inline

Get the target position.

Parameters
currTimeThe current timestamp.
Returns
navtypes::Vectord<dim> The target position if hasTarget() is true, else 0 vector.

◆ getTotalTime()

template<int dim>
std::optional< util::dseconds > control::TrapezoidalVelocityProfile< dim >::getTotalTime ( ) const
inline

Get the total time it takes to perform the profile.

Returns
std::optional<util::dseconds> The total time. If hasTarget() is false, returns empty optional.

◆ hasTarget()

template<int dim>
bool control::TrapezoidalVelocityProfile< dim >::hasTarget ( ) const
inline

Check if a profile has been calculated.

Returns
bool True iff setTarget() has been called since construction or the last reset.

◆ setTarget() [1/2]

template<int dim>
void control::TrapezoidalVelocityProfile< dim >::setTarget ( robot::types::datatime_t currTime,
const navtypes::Vectord< dim > & startPos,
const navtypes::Vectord< dim > & endPos )
inline

Calculate a profile, assuming the mechanism begins and ends at rest.

Parameters
currTimeThe current timestamp.
startPosThe position the profile starts at.
endPosThe position the profile ends at.

◆ setTarget() [2/2]

template<int dim>
void control::TrapezoidalVelocityProfile< dim >::setTarget ( robot::types::datatime_t currTime,
const std::array< double, dim > & startPos,
const std::array< double, dim > & endPos )
inline

Calculate a profile, assuming the mechanism begins and ends at rest.

Parameters
currTimeThe current timestamp.
startPosThe position the profile starts at.
endPosThe position the profile ends at.

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