speed.h
Go to the documentation of this file.
00001 /* -*- mode: C++ -*-
00002  *
00003  *  Copyright (C) 2005, 2007, 2009, 2011 Austin Robot Technology
00004  *  License: Modified BSD Software License Agreement
00005  * 
00006  *  $Id: speed.h 1539 2011-05-09 04:09:20Z jack.oquin $
00007  */
00008 
00024 #ifndef __SPEED_H_
00025 #define __SPEED_H_
00026 
00027 #include <ros/ros.h>
00028 #include <art/pid2.h>
00029 #include <art_pilot/PilotConfig.h>
00030 
00031 // epsilon values for brake and throttle requests
00032 #define EPSILON_BRAKE 0.01
00033 #define EPSILON_THROTTLE 0.01
00034 
00036 class SpeedControl
00037 {
00038  public:
00039 
00040   SpeedControl()
00041   {
00042     // initialize private node handle for getting parameter settings
00043     node_ = ros::NodeHandle("~");
00044   };
00045 
00055   virtual void adjust(float speed, float error,
00056                       float *brake_req, float *throttle_req) = 0;
00057 
00059   virtual void configure(art_pilot::PilotConfig &newconfig) = 0;
00060 
00062   virtual void reset(void) = 0;
00063 
00064   virtual void set_brake_position(float position)
00065   {
00066     brake_position_ = position;
00067   }
00068   virtual void set_throttle_position(float position)
00069   {
00070     throttle_position_ = position;
00071   }
00072 
00073 protected:
00074 
00075   ros::NodeHandle node_;                // private node handle for parameters
00076   float brake_position_;
00077   float throttle_position_;
00078 };
00079 
00081 class SpeedControlMatrix: public SpeedControl
00082 {
00083  public:
00084 
00085   SpeedControlMatrix();
00086   virtual ~SpeedControlMatrix();
00087   virtual void adjust(float speed, float error,
00088                       float *brake_req, float *throttle_req);
00089   virtual void configure(art_pilot::PilotConfig &newconfig);
00090   virtual void reset(void);
00091 
00092  private:
00093 
00094   boost::shared_ptr<Pid> velpid_;       // velocity PID control
00095 };
00096 
00098 class SpeedControlPID: public SpeedControl
00099 {
00100  public:
00101 
00102   SpeedControlPID();
00103   virtual ~SpeedControlPID();
00104   virtual void adjust(float speed, float error,
00105                       float *brake_req, float *throttle_req);
00106   virtual void configure(art_pilot::PilotConfig &newconfig);
00107   virtual void reset(void);
00108 
00109  private:
00110 
00111   // When true, brake is the controlling device, otherwise throttle.
00112   bool braking_;
00113 
00114   boost::shared_ptr<Pid> brake_pid_;    // Brake_Pilot control PID
00115   boost::shared_ptr<Pid> throttle_pid_; // Throttle control PID
00116 };
00117 
00118 #endif // __SPEED_H_
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


art_pilot
Author(s): Austin Robot Technology, Jack O'Quin
autogenerated on Tue Sep 24 2013 10:44:02