ref_generator.h
Go to the documentation of this file.
00001 
00013 /************************************************************************
00014  *      Copyright (C) 2012 Eindhoven University of Technology (TU/e).           *
00015  *      All rights reserved.                                                                                            *
00016 *************************************************************************
00017  *      Redistribution and use in source and binary forms, with or without      *
00018  *      modification, are permitted provided that the following conditions      *
00019  *      are met:                                                                                                                        *
00020  *                                                                                                                                              *
00021  *              1.      Redistributions of source code must retain the above            *
00022  *                      copyright notice, this list of conditions and the following *
00023  *                      disclaimer.                                                                                                     *
00024  *                                                                                                                                              *
00025  *              2.      Redistributions in binary form must reproduce the above         *
00026  *                      copyright notice, this list of conditions and the following *
00027  *                      disclaimer in the documentation and/or other materials          *
00028  *                      provided with the distribution.                                                         *
00029  *                                                                                                                                              *
00030  *      THIS SOFTWARE IS PROVIDED BY TU/e "AS IS" AND ANY EXPRESS OR            *
00031  *      IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED          *
00032  *      WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE      *
00033  *      ARE DISCLAIMED. IN NO EVENT SHALL TU/e OR CONTRIBUTORS BE LIABLE        *
00034  *      FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR            *
00035  *      CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT       *
00036  *      OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS;         *
00037  *      OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF           *
00038  *      LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT                       *
00039  *      (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE       *
00040  *      USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH        *
00041  *      DAMAGE.                                                                                                                         *
00042  *                                                                                                                                              *
00043  *      The views and conclusions contained in the software and                         *
00044  *      documentation are those of the authors and should not be                        *
00045  *      interpreted as representing official policies, either expressed or      *
00046  *      implied, of TU/e.                                                                                                       *
00047  ************************************************************************/
00048 
00049 #include <ros/ros.h>
00050 
00051 namespace controller {
00052 
00053 class RefGenerator {
00054 
00055 private:
00056 
00057         double pos_; //the current position of the joint to generate a reference for
00058         double vel_; //the current velocity of the joint to generate a reference for
00059         double acc_; //the current acceleration of the joint to generate a reference for
00060 
00061         double max_vel_; //the maximum allowed velocity of the joint to generate a reference for
00062         double max_acc_; //the maximum allowed acceleration of the joint to generate a reference for
00063 
00064         const static double EPSILON = 1e-5; //error margin
00065 
00069         int signum(double a);
00070 
00071 public:
00081         RefGenerator(double current_x, double max_vel, double max_acc);
00082 
00086         ~RefGenerator();
00087 
00091         void setCurrentPosition(double x);
00092 
00096         void setCurrentVelocity(double vel);
00097 
00101         double getPositionReference();
00102 
00106         double getVelocityReference();
00107 
00111         double getAccelerationReference();
00112 
00122         void generate(double x_desired, double dt, bool force_stop);
00123 
00124 };
00125 
00126 
00127 }
00128 


amigo_gazebo
Author(s): Rob Janssen
autogenerated on Tue Jan 7 2014 11:43:55