BaseController.h
Go to the documentation of this file.
00001 
00020 #ifndef __BASE_CONTROLLER__
00021 #define __BASE_CONTROLLER__
00022 
00023 #include "RobotState.h"
00024 #include <boost/thread/mutex.hpp>
00025 #include "geometry_msgs/Twist.h"
00026 #include "CanListener.h"
00027 
00031 class BaseController
00032 {
00033  private:
00034     //Current RoboterState
00035     RobotState *state;
00036     CanListener *canListener;
00037     boost::mutex mutex;
00038     //Messages from Ros
00039     geometry_msgs::Twist cmd;
00040 
00041 
00042     int initAX10420();
00043     void writeDataToCan(float vleft, float vright,  float max_speed);
00044     bool enableMotor(int ax10420);
00045     float calculateVelocity(bool left, float speed, float velocity_old);
00046 
00047 public:
00051     void setTargetVelocity(const geometry_msgs::Twist &twist);
00052     BaseController(RobotState *state, CanListener *canListener1):state(state)
00053     {
00054         canListener = canListener1;
00055     };
00060     void run();
00061 
00068     double calculateAdapter(double required_velocity, double real_velocity, double adapter);
00069 
00070 };
00071 
00072 #endif


asr_mild_base_driving
Author(s): Aumann Florian, Borella Jocelyn, Dehmani Souheil, Marek Felix, Meißner Pascal, Reckling Reno
autogenerated on Thu Jun 6 2019 22:02:58