#include <sot/torque_control/utils/trajectory-generators.hh>
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) |
![]() | |
AbstractTrajectoryGenerator (double dt, double traj_time, const Eigen::VectorXd &x_init, const Eigen::VectorXd &x_final) | |
AbstractTrajectoryGenerator (double dt, double traj_time, Eigen::VectorXd::Index size) | |
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 double &x_final) |
virtual bool | set_final_point (const Eigen::VectorXd &x_final) |
virtual bool | set_initial_point (const double &x_init) |
virtual bool | set_initial_point (const Eigen::VectorXd &x_init) |
Protected Attributes | |
int | m_counter |
int | m_counter_max |
Eigen::VectorXd | m_ddx0 |
bool | m_is_accelerating |
![]() | |
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 | |
![]() | |
virtual void | resizeAllData (Eigen::VectorXd::Index size) |
void | sendMsg (const std::string &msg, MsgType t=MSG_TYPE_INFO, const char *file="", int line=0) |
Endless piece-wise constant acceleration trajectory generator.
Definition at line 334 of file trajectory-generators.hh.
|
inline |
Definition at line 342 of file trajectory-generators.hh.
|
inlinevirtual |
Implements AbstractTrajectoryGenerator.
Definition at line 354 of file trajectory-generators.hh.
References ConstantAccelerationTrajectoryGenerator::m_counter, ConstantAccelerationTrajectoryGenerator::m_counter_max, AbstractTrajectoryGenerator::m_ddx, ConstantAccelerationTrajectoryGenerator::m_ddx0, AbstractTrajectoryGenerator::m_dt, AbstractTrajectoryGenerator::m_dx, ConstantAccelerationTrajectoryGenerator::m_is_accelerating, AbstractTrajectoryGenerator::m_t, AbstractTrajectoryGenerator::m_traj_time, AbstractTrajectoryGenerator::m_x, AbstractTrajectoryGenerator::m_x_final, and AbstractTrajectoryGenerator::m_x_init.
|
inlinevirtual |
Reimplemented from AbstractTrajectoryGenerator.
Definition at line 373 of file trajectory-generators.hh.
|
inlinevirtual |
Reimplemented from AbstractTrajectoryGenerator.
Definition at line 345 of file trajectory-generators.hh.
References ConstantAccelerationTrajectoryGenerator::m_counter, ConstantAccelerationTrajectoryGenerator::m_counter_max, AbstractTrajectoryGenerator::m_dt, ConstantAccelerationTrajectoryGenerator::m_is_accelerating, AbstractTrajectoryGenerator::m_traj_time, and AbstractTrajectoryGenerator::set_trajectory_time().
|
protected |
Definition at line 337 of file trajectory-generators.hh.
Referenced by ConstantAccelerationTrajectoryGenerator::compute_next_point(), and ConstantAccelerationTrajectoryGenerator::set_trajectory_time().
|
protected |
Definition at line 338 of file trajectory-generators.hh.
Referenced by ConstantAccelerationTrajectoryGenerator::compute_next_point(), and ConstantAccelerationTrajectoryGenerator::set_trajectory_time().
|
protected |
Definition at line 339 of file trajectory-generators.hh.
Referenced by ConstantAccelerationTrajectoryGenerator::compute_next_point().
|
protected |
Definition at line 336 of file trajectory-generators.hh.
Referenced by ConstantAccelerationTrajectoryGenerator::compute_next_point(), and ConstantAccelerationTrajectoryGenerator::set_trajectory_time().