sot-torque-control  1.6.4
Collection of dynamic-graph entities aimed at implementing torque control on different robots.
ConstantAccelerationTrajectoryGenerator Class Reference

#include <sot/torque_control/utils/trajectory-generators.hh>

Inheritance diagram for ConstantAccelerationTrajectoryGenerator:
Collaboration diagram for ConstantAccelerationTrajectoryGenerator:

Public Member Functions

 ConstantAccelerationTrajectoryGenerator (double dt, double traj_time, int size)
 
const Eigen::VectorXd & compute_next_point ()
 
virtual bool isTrajectoryEnded ()
 
virtual bool set_trajectory_time (double traj_time)
 
- Public Member Functions inherited from AbstractTrajectoryGenerator
 AbstractTrajectoryGenerator (double dt, double traj_time, Eigen::VectorXd::Index size)
 
 AbstractTrajectoryGenerator (double dt, double traj_time, const Eigen::VectorXd &x_init, const Eigen::VectorXd &x_final)
 
virtual const Eigen::VectorXd & get_final_point ()
 
virtual const Eigen::VectorXd & get_initial_point ()
 
virtual const Eigen::VectorXd & getAcc ()
 
virtual const Eigen::VectorXd & getPos ()
 
virtual const Eigen::VectorXd & getVel ()
 
virtual bool set_final_point (const Eigen::VectorXd &x_final)
 
virtual bool set_final_point (const double &x_final)
 
virtual bool set_initial_point (const Eigen::VectorXd &x_init)
 
virtual bool set_initial_point (const double &x_init)
 

Protected Attributes

int m_counter
 
int m_counter_max
 
Eigen::VectorXd m_ddx0
 
bool m_is_accelerating
 
- Protected Attributes inherited from AbstractTrajectoryGenerator
Eigen::VectorXd m_ddx
 current velocity More...
 
double m_dt
 time to go from x_init to x_final (sec) More...
 
Eigen::VectorXd m_dx
 current position More...
 
Eigen::VectorXd::Index m_size
 current time More...
 
double m_t
 control dt (sampling period of the trajectory) More...
 
double m_traj_time
 final position More...
 
Eigen::VectorXd m_x
 
Eigen::VectorXd m_x_final
 initial position More...
 
Eigen::VectorXd m_x_init
 current acceleration More...
 

Additional Inherited Members

- Protected Member Functions inherited from AbstractTrajectoryGenerator
virtual void resizeAllData (Eigen::VectorXd::Index size)
 
void sendMsg (const std::string &msg, MsgType t=MSG_TYPE_INFO, const char *file="", int line=0)
 

Detailed Description

Endless piece-wise constant acceleration trajectory generator.

Definition at line 348 of file trajectory-generators.hh.

Constructor & Destructor Documentation

◆ ConstantAccelerationTrajectoryGenerator()

ConstantAccelerationTrajectoryGenerator ( double  dt,
double  traj_time,
int  size 
)
inline

Definition at line 359 of file trajectory-generators.hh.

Member Function Documentation

◆ compute_next_point()

const Eigen::VectorXd& compute_next_point ( )
inlinevirtual

Implements AbstractTrajectoryGenerator.

Definition at line 372 of file trajectory-generators.hh.

◆ isTrajectoryEnded()

virtual bool isTrajectoryEnded ( )
inlinevirtual

Reimplemented from AbstractTrajectoryGenerator.

Definition at line 391 of file trajectory-generators.hh.

◆ set_trajectory_time()

virtual bool set_trajectory_time ( double  traj_time)
inlinevirtual

Reimplemented from AbstractTrajectoryGenerator.

Definition at line 363 of file trajectory-generators.hh.

Member Data Documentation

◆ m_counter

int m_counter
protected

Definition at line 352 of file trajectory-generators.hh.

◆ m_counter_max

int m_counter_max
protected

Definition at line 353 of file trajectory-generators.hh.

◆ m_ddx0

Eigen::VectorXd m_ddx0
protected

Definition at line 355 of file trajectory-generators.hh.

◆ m_is_accelerating

bool m_is_accelerating
protected

Definition at line 351 of file trajectory-generators.hh.


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