CanListener.h
Go to the documentation of this file.
1 
20 #ifndef __CAN_LISTENER__
21 #define __CAN_LISTENER__
22 
23 #include "RobotState.h"
24 
29 {
30  private:
31 
32  //Variables
33  //Current RoboterState.
38  double left_average;
39  double right_average;
40  //Average over X succressive measures.
44  int counter;
45 
49  void initalize();
53  geometry_msgs::TransformStamped getOdomTF(ros::Time current_time);
57  nav_msgs::Odometry getOdomMsg(ros::Time current_time);
61  bool gettingData();
65  int overflowDetection(int ticks, int ticks_old);
69  void movingForward(double d, double d_time);
73  void turningInPlace(double t, double d_time);
77  void otherMovement(double d, double t, double d_time);
81  double calculateAverage(double velocity_average[], double velocity);
82 
83 public:
84  CanListener(RobotState *state):state(state) {};
88  void run();
89 
93  double get_velocity_right();
94  double get_velocity_left();
95 
96  struct can_frame frame;
97 };
98 
99 #endif
double left_average
Definition: CanListener.h:38
CanListener(RobotState *state)
Definition: CanListener.h:84
void otherMovement(double d, double t, double d_time)
int average_size
Definition: CanListener.h:41
double right_velocity_average[50]
Definition: CanListener.h:43
int overflowDetection(int ticks, int ticks_old)
double impulses_per_mm_left
Definition: CanListener.h:35
void turningInPlace(double t, double d_time)
void initalize()
Definition: CanListener.cpp:33
nav_msgs::Odometry getOdomMsg(ros::Time current_time)
Definition: CanListener.cpp:70
bool gettingData()
Definition: CanListener.cpp:97
double get_velocity_left()
double calculateAverage(double velocity_average[], double velocity)
RobotState * state
Definition: CanListener.h:34
double impulses_per_mm_right
Definition: CanListener.h:36
double right_average
Definition: CanListener.h:39
void movingForward(double d, double d_time)
geometry_msgs::TransformStamped getOdomTF(ros::Time current_time)
Definition: CanListener.cpp:49
double wheel_distance
Definition: CanListener.h:37
double left_velocity_average[50]
Definition: CanListener.h:42
struct can_frame frame
Definition: CanListener.h:96
double get_velocity_right()


asr_mild_base_driving
Author(s): Aumann Florian, Borella Jocelyn, Dehmani Souheil, Marek Felix, Meißner Pascal, Reckling Reno
autogenerated on Mon Jun 10 2019 12:43:40