CanListener.h
Go to the documentation of this file.
00001 
00020 #ifndef __CAN_LISTENER__
00021 #define __CAN_LISTENER__
00022 
00023 #include "RobotState.h"
00024 
00028 class CanListener
00029 {
00030  private:
00031 
00032     //Variables
00033     //Current RoboterState.
00034     RobotState *state;
00035     double impulses_per_mm_left;
00036     double impulses_per_mm_right;
00037     double wheel_distance;
00038     double left_average;
00039     double right_average;
00040     //Average over X succressive measures.
00041     int average_size;
00042     double left_velocity_average[50];
00043     double right_velocity_average[50];
00044     int counter;
00045 
00049     void initalize();
00053     geometry_msgs::TransformStamped getOdomTF(ros::Time current_time);
00057     nav_msgs::Odometry getOdomMsg(ros::Time current_time);
00061     bool gettingData();
00065     int overflowDetection(int ticks, int ticks_old);
00069     void movingForward(double d, double d_time);
00073     void turningInPlace(double t, double d_time);
00077     void otherMovement(double d, double t, double d_time);
00081     double calculateAverage(double velocity_average[], double velocity);
00082 
00083 public:
00084     CanListener(RobotState *state):state(state) {};
00088     void run();
00089 
00093     double get_velocity_right();
00094     double get_velocity_left();
00095 
00096     struct can_frame frame;
00097 };
00098 
00099 #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