6 #include <dynamic-graph/factory.h> 
    8 #include <sot/core/debug.hh> 
    9 #include <sot/core/stop-watch.hh> 
   13 #include "../include/sot/torque_control/stc-commands.hh" 
   20 using namespace dynamicgraph::command;
 
   22 using namespace Eigen;
 
   25 #define PROFILE_POSITION_DESIRED_COMPUTATION \ 
   26   "TrajGen: reference joint traj computation              " 
   27 #define PROFILE_FORCE_DESIRED_COMPUTATION \ 
   28   "TrajGen: reference force computation                   " 
   36                                    "JointTrajectoryGenerator");
 
   43       CONSTRUCT_SIGNAL_IN(base6d_encoders, 
dynamicgraph::Vector),
 
   44       CONSTRUCT_SIGNAL_OUT(q, 
dynamicgraph::Vector, m_base6d_encodersSIN),
 
   46       CONSTRUCT_SIGNAL_OUT(ddq, 
dynamicgraph::Vector, m_qSOUT),
 
   51       m_initSucceeded(false),
 
   53       m_robot_util(RefVoidRobotUtil()) {
 
   54   BIND_SIGNAL_TO_FUNCTION(fRightFoot, OUT, dynamicgraph::Vector);
 
   55   BIND_SIGNAL_TO_FUNCTION(fLeftFoot, OUT, dynamicgraph::Vector);
 
   56   BIND_SIGNAL_TO_FUNCTION(fRightHand, OUT, dynamicgraph::Vector);
 
   57   BIND_SIGNAL_TO_FUNCTION(fLeftHand, OUT, dynamicgraph::Vector);
 
   68   Entity::signalRegistration(m_qSOUT << m_dqSOUT << m_ddqSOUT
 
   69                                      << m_base6d_encodersSIN << m_fRightFootSOUT
 
   70                                      << m_fLeftFootSOUT << m_fRightHandSOUT
 
   76                               docCommandVoid2(
"Initialize the entity.",
 
   77                                               "Time period in seconds (double)",
 
   78                                               "robotRef (string)")));
 
   84           docCommandVoid1(
"Get the current angle of the specified joint.",
 
   85                           "Joint name (string)")));
 
   89   addCommand(
"isTrajectoryEnded",
 
   91                  *
this, 
"Return whether all joint trajectories have ended"));
 
   93   addCommand(
"playTrajectoryFile",
 
   97                      "Play the trajectory read from the specified text file.",
 
   98                      "(string) File name, path included")));
 
  100   addCommand(
"startSinusoid",
 
  104                      "Start an infinite sinusoid motion.",
 
  105                      "(string) joint name", 
"(double) final angle in radians",
 
  106                      "(double) time to reach the final angle in sec")));
 
  108   addCommand(
"startTriangle",
 
  112                      "Start an infinite triangle wave.", 
"(string) joint name",
 
  113                      "(double) final angle in radians",
 
  114                      "(double) time to reach the final angle in sec",
 
  115                      "(double) time to accelerate in sec")));
 
  117   addCommand(
"startConstAcc",
 
  121                      "Start an infinite trajectory with piece-wise constant " 
  123                      "(string) joint name", 
"(double) final angle in radians",
 
  124                      "(double) time to reach the final angle in sec")));
 
  127       "startForceSinusoid",
 
  130           docCommandVoid4(
"Start an infinite sinusoid force.",
 
  131                           "(string) force name", 
"(int) force axis in [0, 5]",
 
  132                           "(double) final 1d force in N or Nm",
 
  133                           "(double) time to reach the final force in sec")));
 
  151           docCommandVoid5(
"Start a linear-chirp motion.", 
"(string) joint name",
 
  152                           "(double) final angle in radians",
 
  153                           "(double) initial frequency [Hz]",
 
  154                           "(double) final frequency [Hz]",
 
  155                           "(double) trajectory time [sec]")));
 
  157   addCommand(
"startForceLinChirp",
 
  160                  docCommandVoid6(
"Start a linear-chirp force traj.",
 
  161                                  "(string) force name", 
"(int) force axis",
 
  162                                  "(double) final force in N/Nm",
 
  163                                  "(double) initial frequency [Hz]",
 
  164                                  "(double) final frequency [Hz]",
 
  165                                  "(double) trajectory time [sec]")));
 
  167   addCommand(
"moveJoint",
 
  171                      "Move the joint to the specified angle with a minimum " 
  173                      "(string) joint name", 
"(double) final angle in radians",
 
  174                      "(double) time to reach the final angle in sec")));
 
  180           docCommandVoid4(
"Move the force to the specified value with a " 
  181                           "minimum jerk trajectory.",
 
  182                           "(string) force name", 
"(int) force axis",
 
  183                           "(double) final force in N/Nm",
 
  184                           "(double) time to reach the final force in sec")));
 
  189                  docCommandVoid1(
"Stop the motion of the specified joint, or " 
  190                                  "of all joints if no joint name is specified.",
 
  191                                  "(string) joint name")));
 
  196                        docCommandVoid1(
"Stop the specified force trajectort",
 
  197                                        "(string) force name (rh,lh,lf,rf)")));
 
  201                                     const std::string& robotRef) {
 
  203   std::string localName(robotRef);
 
  204   if (isNameInRobotUtil(localName))
 
  207     SEND_MSG(
"You should have an entity controller manager initialized before",
 
  212   if (dt <= 0.0) 
return SEND_MSG(
"Timestep must be positive", MSG_TYPE_ERROR);
 
  225   for (
long unsigned int i = 0; i < 
m_robot_util->m_nbJoints; i++) {
 
  238   for (
int i = 0; i < 4; i++) {
 
  253   if (!m_initSucceeded) {
 
  254     SEND_WARNING_STREAM_MSG(
 
  255         "Cannot compute signal positionDes before initialization!");
 
  263       const dynamicgraph::Vector& base6d_encoders = m_base6d_encodersSIN(iter);
 
  264       if (base6d_encoders.size() !=
 
  265           static_cast<Eigen::VectorXd::Index
>(m_robot_util->m_nbJoints + 6)) {
 
  266         SEND_ERROR_STREAM_MSG(
"Unexpected size of signal base6d_encoder " +
 
  267                               toString(base6d_encoders.size()) + 
" " +
 
  268                               toString(m_robot_util->m_nbJoints + 6));
 
  271       for (
unsigned int i = 0; i < m_robot_util->m_nbJoints; i++)
 
  272         m_noTrajGen[i]->set_initial_point(base6d_encoders(6 + i));
 
  277         static_cast<Eigen::VectorXd::Index
>(m_robot_util->m_nbJoints))
 
  278       s.resize(m_robot_util->m_nbJoints);
 
  280     if (m_status[0] == JTG_TEXT_FILE) {
 
  281       const VectorXd& qRef = m_textFileTrajGen->compute_next_point();
 
  282       for (
unsigned int i = 0; i < m_robot_util->m_nbJoints; i++) {
 
  284         if (m_textFileTrajGen->isTrajectoryEnded()) {
 
  285           m_noTrajGen[i]->set_initial_point(s(i));
 
  286           m_status[i] = JTG_STOP;
 
  289       if (m_textFileTrajGen->isTrajectoryEnded())
 
  290         SEND_MSG(
"Text file trajectory ended.", MSG_TYPE_INFO);
 
  292       for (
unsigned int i = 0; i < m_robot_util->m_nbJoints; i++) {
 
  293         s(i) = m_currentTrajGen[i]->compute_next_point()(0);
 
  294         if (m_currentTrajGen[i]->isTrajectoryEnded()) {
 
  295           m_currentTrajGen[i] = m_noTrajGen[i];
 
  296           m_noTrajGen[i]->set_initial_point(s(i));
 
  297           m_status[i] = JTG_STOP;
 
  298           SEND_MSG(
"Trajectory of joint " + m_robot_util->get_name_from_id(i) +
 
  311   if (!m_initSucceeded) {
 
  312     SEND_WARNING_STREAM_MSG(
 
  313         "Cannot compute signal positionDes before initialization! iter: " +
 
  318   if (s.size() != 
static_cast<Eigen::VectorXd::Index
>(m_robot_util->m_nbJoints))
 
  319     s.resize(m_robot_util->m_nbJoints);
 
  320   if (m_status[0] == JTG_TEXT_FILE) {
 
  321     for (
unsigned int i = 0; i < m_robot_util->m_nbJoints; i++)
 
  322       s(i) = m_textFileTrajGen->getVel()[i];
 
  324     for (
unsigned int i = 0; i < m_robot_util->m_nbJoints; i++)
 
  325       s(i) = m_currentTrajGen[i]->getVel()(0);
 
  331   if (!m_initSucceeded) {
 
  332     SEND_WARNING_STREAM_MSG(
 
  333         "Cannot compute signal positionDes before initialization!" +
 
  338   if (s.size() != 
static_cast<Eigen::VectorXd::Index
>(m_robot_util->m_nbJoints))
 
  339     s.resize(m_robot_util->m_nbJoints);
 
  341   if (m_status[0] == JTG_TEXT_FILE) {
 
  342     for (
unsigned int i = 0; i < m_robot_util->m_nbJoints; i++)
 
  343       s(i) = m_textFileTrajGen->getAcc()[i];
 
  345     for (
unsigned int i = 0; i < m_robot_util->m_nbJoints; i++)
 
  346       s(i) = m_currentTrajGen[i]->getAcc()(0);
 
  354   generateReferenceForceSignal(
 
  356       static_cast<int>(m_robot_util->m_force_util.get_force_id_right_foot()), s,
 
  362   generateReferenceForceSignal(
 
  364       static_cast<int>(m_robot_util->m_force_util.get_force_id_left_foot()), s,
 
  370   generateReferenceForceSignal(
 
  372       static_cast<int>(m_robot_util->m_force_util.get_force_id_right_hand()), s,
 
  378   generateReferenceForceSignal(
 
  380       static_cast<int>(m_robot_util->m_force_util.get_force_id_left_hand()), s,
 
  386     const std::string& forceName, 
int fid, dynamicgraph::Vector& s, 
int iter) {
 
  388     SEND_WARNING_STREAM_MSG(
"Cannot compute signal " + forceName +
 
  389                             " before initialization!");
 
  395     if (s.size() != 6) s.resize(6);
 
  406     for (
unsigned int i = 0; i < 6; i++) s(i) = fr(i);
 
  413       SEND_MSG(
"Trajectory of force " + forceName + 
" ended.", MSG_TYPE_INFO);
 
  428   const dynamicgraph::Vector& base6d_encoders =
 
  429       m_base6d_encodersSIN.accessCopy();
 
  430   SEND_MSG(
"Current angle of joint " + jointName + 
" is " +
 
  431                toString(base6d_encoders(6 + i)),
 
  438     for (
unsigned int i = 0; i < 
m_robot_util->m_nbJoints; i++) {
 
  441         SEND_MSG(
"Text file trajectory not ended.", MSG_TYPE_INFO);
 
  446     for (
unsigned int i = 0; i < 
m_robot_util->m_nbJoints; i++) {
 
  449         SEND_MSG(
"Trajectory of joint " + 
m_robot_util->get_name_from_id(i) +
 
  461     return SEND_MSG(
"Cannot start sinusoid before initialization!",
 
  464   for (
unsigned int i = 0; i < 
m_robot_util->m_nbJoints; i++)
 
  466       return SEND_MSG(
"You cannot joint " + 
m_robot_util->get_name_from_id(i) +
 
  467                           " because it is already controlled.",
 
  471     return SEND_MSG(
"Error while loading text file " + fileName,
 
  476   bool needToMoveToInitConf = 
false;
 
  478   for (
unsigned int i = 0; i < 
m_robot_util->m_nbJoints; i++)
 
  480       needToMoveToInitConf = 
true;
 
  482                    " is too far from initial configuration so first i will " 
  488   if (needToMoveToInitConf) {
 
  489     for (
unsigned int i = 0; i < 
m_robot_util->m_nbJoints; i++) {
 
  501   for (
unsigned int i = 0; i < 
m_robot_util->m_nbJoints; i++) {
 
  507                                              const double& qFinal,
 
  508                                              const double& time) {
 
  510     return SEND_MSG(
"Cannot start sinusoid before initialization!",
 
  516     return SEND_MSG(
"Trajectory time must be a positive number",
 
  520         "You cannot move the specified joint because it is already controlled.",
 
  526       "Set initial point of sinusoid to " + toString(
m_sinTrajGen[i]->getPos()),
 
  535                                              const double& qFinal,
 
  537                                              const double& Tacc) {
 
  539     return SEND_MSG(
"Cannot start triangle before initialization!",
 
  546         "You cannot move the specified joint because it is already controlled.",
 
  551   SEND_MSG(
"Set initial point of triangular trajectory to " +
 
  557     return SEND_MSG(
"Trajectory time cannot be negative.", MSG_TYPE_ERROR);
 
  561         "Acceleration time cannot be negative or larger than half the " 
  570                                              const double& qFinal,
 
  571                                              const double& time) {
 
  574         "Cannot start constant-acceleration trajectory before initialization!",
 
  580     return SEND_MSG(
"Trajectory time must be a positive number",
 
  584         "You cannot move the specified joint because it is already controlled.",
 
  589   SEND_MSG(
"Set initial point of const-acc trajectory to " +
 
  600                                                   const double& fFinal,
 
  601                                                   const double& time) {
 
  603     return SEND_MSG(
"Cannot start force sinusoid before initialization!",
 
  609     return SEND_MSG(
"Trajectory time must be a positive number",
 
  611   if (axis < 0 || axis > 5)
 
  612     return SEND_MSG(
"Axis must be between 0 and 5", MSG_TYPE_ERROR);
 
  615         "You cannot move the specified force because it is already controlled.",
 
  622   SEND_MSG(
"Set initial point of sinusoid to " +
 
  625   currentF[axis] = fFinal;
 
  633                                                 const double& qFinal,
 
  636                                                 const double& time) {
 
  638     return SEND_MSG(
"Cannot start linear chirp before initialization!",
 
  644     return SEND_MSG(
"Trajectory time must be a positive number",
 
  648         "You cannot move the specified joint because it is already controlled.",
 
  653         "f0 " + toString(f0) + 
" cannot to be more than f1 " + toString(f1),
 
  656     return SEND_MSG(
"Frequency has to be positive " + toString(f0),
 
  660     return SEND_MSG(
"Error while setting initial point " +
 
  664     return SEND_MSG(
"Error while setting final point " + toString(qFinal),
 
  667     return SEND_MSG(
"Error while setting trajectory time " + toString(time),
 
  670     return SEND_MSG(
"Error while setting initial frequency " + toString(f0),
 
  673     return SEND_MSG(
"Error while setting final frequency " + toString(f1),
 
  680     const string& forceName, 
const int& axis, 
const double& fFinal,
 
  681     const double& f0, 
const double& f1, 
const double& time) {
 
  683     return SEND_MSG(
"Cannot start force linear chirp before initialization!",
 
  689     return SEND_MSG(
"Trajectory time must be a positive number",
 
  693         "You cannot move the specified force because it is already controlled.",
 
  698         "f0 " + toString(f0) + 
" cannot to be more than f1 " + toString(f1),
 
  701     return SEND_MSG(
"Frequency has to be positive " + toString(f0),
 
  706     return SEND_MSG(
"Error while setting initial point " +
 
  709   currentF[axis] = fFinal;
 
  711     return SEND_MSG(
"Error while setting final point " + toString(fFinal),
 
  714     return SEND_MSG(
"Error while setting trajectory time " + toString(time),
 
  717           Vector6d::Constant(f0)))
 
  718     return SEND_MSG(
"Error while setting initial frequency " + toString(f0),
 
  721     return SEND_MSG(
"Error while setting final frequency " + toString(f1),
 
  728                                          const double& qFinal,
 
  729                                          const double& time) {
 
  731     return SEND_MSG(
"Cannot move joint before initialization!", MSG_TYPE_ERROR);
 
  736     return SEND_MSG(
"Trajectory time must be a positive number",
 
  740         "You cannot move the specified joint because it is already controlled.",
 
  752                                          const int& axis, 
const double& fFinal,
 
  753                                          const double& time) {
 
  755     return SEND_MSG(
"Cannot move force before initialization!", MSG_TYPE_ERROR);
 
  760     return SEND_MSG(
"Trajectory time must be a positive number",
 
  764         "You cannot move the specified force because it is already controlled.",
 
  770   currentF[axis] = fFinal;
 
  779     return SEND_MSG(
"Cannot stop joint before initialization!", MSG_TYPE_ERROR);
 
  781   const dynamicgraph::Vector& base6d_encoders =
 
  782       m_base6d_encodersSIN.accessCopy();
 
  783   if (jointName == 
"all") {
 
  784     for (
unsigned int i = 0; i < 
m_robot_util->m_nbJoints; i++) {
 
  787       m_noTrajGen[i]->set_initial_point(base6d_encoders(6 + i));
 
  796       base6d_encoders(6 + i));  
 
  803     return SEND_MSG(
"Cannot stop force before initialization!", MSG_TYPE_ERROR);
 
  818     const std::string& name, 
unsigned int& 
id) {
 
  822     SEND_MSG(
"The specified joint name does not exist", MSG_TYPE_ERROR);
 
  823     std::stringstream ss;
 
  824     for (map<string, Index>::const_iterator it =
 
  827       ss << it->first << 
", ";
 
  828     SEND_MSG(
"Possible joint names are: " + ss.str(), MSG_TYPE_INFO);
 
  831   id = 
static_cast<unsigned int>(jid);
 
  836     const std::string& name, 
unsigned int& 
id) {
 
  838   Index fid = 
m_robot_util->m_force_util.get_id_from_name(name);
 
  840     SEND_MSG(
"The specified force name does not exist", MSG_TYPE_ERROR);
 
  841     std::stringstream ss;
 
  842     for (map<string, Index>::const_iterator it =
 
  844          it != 
m_robot_util->m_force_util.m_name_to_force_id.end(); it++)
 
  845       ss << it->first << 
", ";
 
  846     SEND_MSG(
"Possible force names are: " + ss.str(), MSG_TYPE_INFO);
 
  849   id = (
unsigned int)fid;
 
  854   JointLimits jl = 
m_robot_util->get_joint_limits_from_id(
id);
 
  856     SEND_MSG(
"Joint " + 
m_robot_util->get_name_from_id(
id) +
 
  857                  ", desired angle " + toString(q) +
 
  858                  " is smaller than lower limit " + toString(jl.lower),
 
  863     SEND_MSG(
"Joint " + 
m_robot_util->get_name_from_id(
id) +
 
  864                  ", desired angle " + toString(q) +
 
  865                  " is larger than upper limit " + toString(jl.upper),
 
  873                                               const Eigen::VectorXd& f) {
 
  874   ForceLimits fl = 
m_robot_util->m_force_util.get_limits_from_id(
id);
 
  875   for (
unsigned int i = 0; i < 6; i++)
 
  876     if (f[i] < fl.lower[i] || f[i] > fl.upper[i]) {
 
  877       SEND_MSG(
"Desired force " + toString(i) +
 
  878                    " is out of range: " + toString(fl.lower[i]) + 
" < " +
 
  879                    toString(f[i]) + 
" < " + toString(fl.upper[i]),
 
  888   ForceLimits fl = 
m_robot_util->m_force_util.get_limits_from_id(
id);
 
  889   if (f < fl.lower[axis] || f > fl.upper[axis]) {
 
  890     SEND_MSG(
"Desired force " + toString(axis) +
 
  891                  " is out of range: " + toString(fl.lower[axis]) + 
" < " +
 
  892                  toString(f) + 
" < " + toString(fl.upper[axis]),
 
  904   os << 
"JointTrajectoryGenerator " << getName();
 
  906     getProfiler().report_all(3, os);
 
  907   } 
catch (ExceptionSignal e) {
 
virtual const Eigen::VectorXd & get_initial_point()
 
virtual bool isTrajectoryEnded()
 
void moveJoint(const std::string &jointName, const double &qFinal, const double &time)
 
void moveForce(const std::string &forceName, const int &axis, const double &fFinal, const double &time)
 
std::vector< SinusoidTrajectoryGenerator * > m_sinTrajGen
 
void startSinusoid(const std::string &jointName, const double &qFinal, const double &time)
 
std::vector< AbstractTrajectoryGenerator * > m_currentTrajGen_force
status of the forces
 
RobotUtilShrPtr m_robot_util
control loop time period
 
void startLinearChirp(const std::string &jointName, const double &qFinal, const double &f0, const double &f1, const double &time)
 
void stopForce(const std::string &forceName)
 
bool isJointInRange(unsigned int id, double q)
 
TextFileTrajectoryGenerator * m_textFileTrajGen
 
bool convertForceNameToForceId(const std::string &name, unsigned int &id)
 
std::vector< LinearChirpTrajectoryGenerator * > m_linChirpTrajGen
 
bool isForceInRange(unsigned int id, const Eigen::VectorXd &f)
 
std::vector< JTG_Status > m_status_force
 
bool generateReferenceForceSignal(const std::string &forceName, int fid, dynamicgraph::Vector &s, int iter)
 
std::vector< LinearChirpTrajectoryGenerator * > m_linChirpTrajGen_force
 
std::vector< NoTrajectoryGenerator * > m_noTrajGen_force
 
std::vector< MinimumJerkTrajectoryGenerator * > m_minJerkTrajGen_force
 
double m_dt
true if it is the first iteration, false otherwise
 
void stop(const std::string &jointName)
 
std::vector< ConstantAccelerationTrajectoryGenerator * > m_constAccTrajGen
 
virtual void display(std::ostream &os) const
 
void startTriangle(const std::string &jointName, const double &qFinal, const double &time, const double &Tacc)
 
bool m_firstIter
true if the entity has been successfully initialized
 
void startForceSinusoid(const std::string &forceName, const int &axis, const double &fFinal, const double &time)
 
JointTrajectoryGenerator(const std::string &name)
 
std::vector< TriangleTrajectoryGenerator * > m_triangleTrajGen
 
std::vector< JTG_Status > m_status
 
void startConstAcc(const std::string &jointName, const double &qFinal, const double &time)
 
void startForceLinearChirp(const std::string &forceName, const int &axis, const double &fFinal, const double &f0, const double &f1, const double &time)
 
std::vector< SinusoidTrajectoryGenerator * > m_sinTrajGen_force
 
std::vector< NoTrajectoryGenerator * > m_noTrajGen
 
bool convertJointNameToJointId(const std::string &name, unsigned int &id)
 
std::vector< AbstractTrajectoryGenerator * > m_currentTrajGen
status of the joints
 
void init(const double &dt, const std::string &robotRef)
 
void getJoint(const std::string &jointName)
 
std::vector< MinimumJerkTrajectoryGenerator * > m_minJerkTrajGen
 
std::vector< int > m_iterForceSignals
 
void playTrajectoryFile(const std::string &fileName)
 
virtual bool loadTextFile(const std::string &fileName)
 
#define PROFILE_FORCE_DESIRED_COMPUTATION
 
#define PROFILE_POSITION_DESIRED_COMPUTATION
 
DEFINE_SIGNAL_OUT_FUNCTION(u, dynamicgraph::Vector)
 
AdmittanceController EntityClassName
 
DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(AdmittanceController, "AdmittanceController")