00001
00002
00003
00004
00005
00006
00007
00008
00009
00017 #ifndef _ANIMATICS_H_
00018 #define _ANIMATICS_H_
00019
00020 #include <stdint.h>
00021
00022 #include <ros/ros.h>
00023
00024 #include "../servo.h"
00025 #include "model_brake.h"
00026
00027
00028 typedef enum
00029 {
00030 Status_Bt = 0x0001,
00031 Status_Br = 0x0002,
00032 Status_Bl = 0x0004,
00033 Status_Bi = 0x0008,
00034 Status_Bw = 0x0010,
00035 Status_Be = 0x0020,
00036 Status_Bh = 0x0040,
00037 Status_Bo = 0x0080,
00038 Status_Bx = 0x0100,
00039 Status_Bp = 0x0200,
00040 Status_Bm = 0x0400,
00041 Status_Bd = 0x0800,
00042 Status_Bu = 0x1000,
00043 Status_Bs = 0x2000,
00044 Status_Ba = 0x4000,
00045 Status_Bk = 0x8000
00046 } brake_status_t;
00047
00048
00049 class Animatics
00050 {
00051 public:
00052
00053 Animatics()
00054 {
00055
00056
00057
00058
00059
00060 ros::NodeHandle node("~");
00061
00062 node.param("encoder_min", encoder_min_, 0);
00063 node.param("encoder_max", encoder_max_, 50000);
00064 encoder_range_ = encoder_max_ - encoder_min_;
00065 ROS_INFO("Animatics encoder range [%d, %d]", encoder_min_, encoder_max_);
00066
00067 node.param("pot_off", pot_off_, 4.9);
00068 node.param("pot_full", pot_full_, 0.49);
00069 pot_range_ = pot_full_ - pot_off_;
00070 ROS_INFO("Animatics potentiometer range [%.3f, %.3f]",
00071 pot_full_, pot_off_);
00072
00073 node.param("pressure_min", pressure_min_, 0.85);
00074 node.param("pressure_max", pressure_max_, 4.5);
00075 pressure_range_ = pressure_max_ - pressure_min_;
00076 ROS_INFO("Animatics pressure range [%.3f, %.3f]",
00077 pressure_min_, pressure_max_);
00078 }
00079 ~Animatics() {};
00080
00081
00082
00083
00084 double pot_off_;
00085 double pot_full_;
00086 double pot_range_;
00087
00088
00089 double pressure_min_;
00090 double pressure_max_;
00091 double pressure_range_;
00092
00093
00094 int encoder_min_;
00095 int encoder_max_;
00096 double encoder_range_;
00097
00098
00099 inline float enc2pos(int encoder_val)
00100 {return ((encoder_val - encoder_min_) / encoder_range_);}
00101 inline int pos2enc(float position)
00102 {return (int) rintf(encoder_min_ + position * encoder_range_);}
00103
00104
00105 inline int clamp_encoder(int value)
00106 {
00107 if (value > encoder_max_) value = encoder_max_;
00108 else if (value < encoder_min_) value = encoder_min_;
00109 return value;
00110 }
00111
00112
00113
00114 inline float pot2pos(float pot_volts)
00115 {return ((pot_volts - pot_off_) / pot_range_);}
00116 inline float pos2pot(float position)
00117 {return position * pot_range_ + pot_off_;}
00118
00119
00120 inline float press2pos(float pressure_volts)
00121 {return ((pressure_volts - pressure_min_) / pressure_range_);}
00122 inline float pos2press(float position)
00123 {return pressure_min_ + position * pressure_range_;}
00124 };
00125
00126
00127 static inline float limit_travel(float position)
00128 {
00129 if (position > 1.0) position = 1.0;
00130 else if (position < 0.0) position = 0.0;
00131 return position;
00132 }
00133
00134 #endif // _ANIMATICS_H_