evarobot_driver.h
Go to the documentation of this file.
00001 #ifndef INCLUDE_EVAROBOT_DRIVER_H_
00002 #define INCLUDE_EVAROBOT_DRIVER_H_
00003 
00004 #include "ros/ros.h"
00005 #include "geometry_msgs/Twist.h"
00006 
00007 
00008 #include "IMPWM.h"
00009 #include "IMGPIO.h"
00010 #include "IMADC.h"
00011 
00012 #include <stdio.h> 
00013 #include <math.h> 
00014 #include <sstream>
00015 
00016 #include <dynamic_reconfigure/server.h>
00017 #include <evarobot_driver/ParamsConfig.h>
00018 
00019 #include <diagnostic_updater/diagnostic_updater.h>
00020 #include <diagnostic_updater/publisher.h>
00021 
00022 #include "im_msgs/SetRGB.h"
00023 #include "im_msgs/Voltage.h"
00024 #include "im_msgs/WheelVel.h"
00025 
00026 #include <ros/console.h>
00027 #include "ErrorCodes.h"
00028 
00029 #include <boost/shared_ptr.hpp>
00030 
00031 using namespace std;
00032 
00033 
00034 bool b_is_received_params = false;
00035 
00036 double g_d_max_lin;
00037 double g_d_max_ang;
00038 double g_d_wheel_separation;
00039 double g_d_wheel_diameter;
00040 
00041 class IMDRIVER
00042 {
00043 public:
00044         IMDRIVER(double d_limit_voltage,
00045                          float f_max_lin_vel, 
00046                          float f_max_ang_vel, 
00047                          float f_wheel_separation, 
00048                          float f_wheel_diameter,
00049                          double d_frequency, 
00050                          unsigned int u_i_counts, 
00051                          double d_duty, 
00052                          int i_mode,
00053                          boost::shared_ptr< IMGPIO > * m1_in, 
00054                          boost::shared_ptr< IMGPIO > * m2_in,
00055                          IMGPIO * m1_en,
00056                          IMGPIO * m2_en,
00057                          IMADC * adc,
00058                          ros::ServiceClient & client,
00059                          double _timeout);
00060                          
00061         ~IMDRIVER();
00062                          
00063         void CallbackWheelVel(const im_msgs::WheelVel::ConstPtr & msg);
00064         void ProduceDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat);
00065         im_msgs::Voltage GetMotorVoltage() const;
00066 
00067         bool CheckMotorCurrent();
00068         bool CheckTimeout();
00069         
00070         void UpdateParams();
00071         void ApplyVel(float f_left_wheel_velocity, float f_right_wheel_velocity);
00072         void Enable();
00073         void Disable();
00074         
00075         int CheckError();
00076         
00077 private:
00078         IMPWM * pwm;
00079         boost::shared_ptr< IMGPIO > * m1_in;
00080         boost::shared_ptr< IMGPIO > * m2_in;
00081         IMGPIO * m1_en;
00082         IMGPIO * m2_en;
00083         
00084         IMADC * adc;
00085         ros::ServiceClient client;
00086         
00087         float f_max_lin_vel; 
00088         float f_max_ang_vel; 
00089         float f_wheel_separation; 
00090         float f_wheel_diameter;
00091 
00092         float f_left_motor_voltage;
00093         float f_right_motor_voltage;
00094 
00095         double d_frequency;
00096         double d_duty;
00097         double d_limit_voltage;
00098         
00099         double d_timeout;
00100         
00101         bool b_motor_error, b_left_motor_error, b_right_motor_error;
00102         bool b_timeout_err;
00103         
00104         unsigned int u_i_counts;
00105         int i_mode;    
00106         int i_const_count;
00107         
00108         ros::Time curr_vel_time;
00109 };
00110 
00111 #endif
00112 


evarobot_driver
Author(s): Mehmet Akcakoca
autogenerated on Fri Feb 12 2016 01:15:19