sobec::FootTrajectory Class Reference

#include <sobec/walk-with-traj/foot_trajectory.hpp>

Public Member Functions

 FootTrajectory (const double &swing_leg_height, const double swing_pose_penetration=0., const double landing_advance=0.)
 FootTrajectory. More...
 
void generate (const double &t_init, const double &t_end, const pinocchio::SE3 &pose_init, const pinocchio::SE3 &pose_end, const bool &constant=false)
 
void update (const double time, const pinocchio::SE3 &pose_end)
 
double min ()
 
double max ()
 
double compute_dt (const double &time)
 
pinocchio::SE3 compute (const double &time)
 
pinocchio::SE3 start ()
 
pinocchio::SE3 end ()
 
eVector3 linear_vel (const double &time)
 
eVector3 angular_vel (const double &time)
 
eVector3 linear_acc (const double &time)
 
eVector3 angular_acc (const double &time)
 
const bool is_constant ()
 

Constructor & Destructor Documentation

◆ FootTrajectory()

sobec::FootTrajectory::FootTrajectory ( const double &  swing_leg_height,
const double  swing_pose_penetration = 0.,
const double  landing_advance = 0. 
)

FootTrajectory.

Parameters
swing_leg_heightdesired height at the apex of the trajectory wrt to the average between init and end height
landing_advanceduration before the final time where the feet pose should be reached

Member Function Documentation

◆ angular_acc()

eVector3 sobec::FootTrajectory::angular_acc ( const double &  time)

◆ angular_vel()

eVector3 sobec::FootTrajectory::angular_vel ( const double &  time)

◆ compute()

pinocchio::SE3 sobec::FootTrajectory::compute ( const double &  time)

◆ compute_dt()

double sobec::FootTrajectory::compute_dt ( const double &  time)

◆ end()

pinocchio::SE3 sobec::FootTrajectory::end ( )

◆ generate()

void sobec::FootTrajectory::generate ( const double &  t_init,
const double &  t_end,
const pinocchio::SE3 &  pose_init,
const pinocchio::SE3 &  pose_end,
const bool &  constant = false 
)

◆ is_constant()

const bool sobec::FootTrajectory::is_constant ( )
inline

◆ linear_acc()

eVector3 sobec::FootTrajectory::linear_acc ( const double &  time)

◆ linear_vel()

eVector3 sobec::FootTrajectory::linear_vel ( const double &  time)

◆ max()

double sobec::FootTrajectory::max ( )

◆ min()

double sobec::FootTrajectory::min ( )

◆ start()

pinocchio::SE3 sobec::FootTrajectory::start ( )

◆ update()

void sobec::FootTrajectory::update ( const double  time,
const pinocchio::SE3 &  pose_end 
)

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