1 #ifndef YOUBOT_JOINTTRAJECTORYCONTROLLER_H 2 #define YOUBOT_JOINTTRAJECTORYCONTROLLER_H 104 void getConfigurationParameter(
double& PParameter,
double& IParameter,
double& DParameter,
double& IClippingMax,
double& IClippingMin);
106 void setConfigurationParameter(
const double PParameter,
const double IParameter,
const double DParameter,
const double IClippingMax,
const double IClippingMin);
110 void cancelCurrentTrajectory();
112 bool isTrajectoryControllerActive();
128 void getQuinticSplineCoefficients(
const double start_pos,
const double start_vel,
const double start_acc,
const double end_pos,
const double end_vel,
const double end_acc,
const double time, std::vector<double>& coefficients);
130 void sampleQuinticSpline(
const std::vector<double>& coefficients,
const double time,
double& position,
double& velocity,
double& acceleration);
132 void getCubicSplineCoefficients(
const double start_pos,
const double start_vel,
const double end_pos,
const double end_vel,
const double time, std::vector<double>& coefficients);
134 void generatePowers(
const int n,
const double x,
double* powers);
136 void sampleSplineWithTimeBounds(
const std::vector<double>& coefficients,
const double duration,
const double time,
double& position,
double& velocity,
double& acceleration);
DataObjectLockFree< boost::shared_ptr< const SpecifiedTrajectory > > current_trajectory_box_
boost::posix_time::ptime time
boost::posix_time::ptime last_time
void setGearRatio(const double &ratio)
boost::posix_time::ptime start_time
Set-point velocity of the joint.
Output part from the EtherCat message of the youBot EtherCat slaves.
std::vector< Segment > SpecifiedTrajectory
void setEncoderTicksPerRound(const int &encoderTicks)
std::vector< double > coef
This DataObject is a Lock-Free implementation, such that reads and writes can happen concurrently wit...
Joint Trajectory representation.
Joint trajectory segment.
double time_till_seg_start
double targetAcceleration
Joint Trajectory Controller.
boost::posix_time::time_duration duration
void setInverseMovementDirection(const bool invDirection)
Set-point angle / position of the joint.