$search
00001 /* -*- mode: C++ -*- 00002 * 00003 * Copyright (C) 2009 Austin Robot Technology, Jack O'Quin 00004 * 00005 * License: Modified BSD Software License Agreement 00006 * 00007 * $Id: devbrake.h 2 2010-01-17 01:54:03Z jack.oquin $ 00008 */ 00009 00017 #ifndef _DEVBRAKE_H_ 00018 #define _DEVBRAKE_H_ 00019 00020 #include <stdio.h> 00021 #include <stdint.h> 00022 #include <math.h> 00023 00024 #include "../servo.h" 00025 #include "model_brake.h" 00026 00027 // One per brake hardware device. 00028 class devbrake: Servo 00029 { 00030 public: 00031 00032 devbrake(bool train); 00033 ~devbrake(); 00034 00035 int Open(const char *port_name); 00036 int Close(); 00037 00038 // brake command methods 00039 int brake_absolute(float position); 00040 int brake_relative(float position); 00041 00042 // accessor method for current position 00043 float get_position(void) {return cur_position;} 00044 00045 // read the primary hardware sensor status 00046 int get_state(float *position, float *potentiometer, 00047 float *encoder, float *pressure); 00048 00049 // These public data are initialized by brake.cc before calling 00050 // setup(), so initial values can be set from the .cfg file. 00051 // Afterwards, the devbrake class updates them whenever it detects 00052 // calibration changes. 00053 00054 // Configuration options: 00055 00056 // potentiometer limits, normally pot_off > pot_full 00057 double pot_off; 00058 double pot_full; 00059 double pot_range; // for calculating fractions 00060 00061 // pressure sensor limits 00062 double pressure_min; 00063 double pressure_max; 00064 double pressure_range; // for calculating fractions 00065 00066 // brake motor encoder limits 00067 double encoder_min; 00068 double encoder_max; // determined by setup() 00069 double encoder_range; // for calculating fractions 00070 00071 private: 00072 00073 // configuration options: 00074 bool training; // use training mode 00075 bool apply_on_exit; // apply brake during shutdown() 00076 double deceleration_threshold; 00077 double deceleration_limit; 00078 double pressure_filter_gain; 00079 bool use_pressure; 00080 00081 // current brake status 00082 bool already_configured; // brake already configured once 00083 brake_status_t cur_status; // last status from servo_cmd() 00084 float cur_pot; // last potentiometer voltage 00085 float cur_pressure; // last brake pressure read 00086 float prev_pressure; // last brake pressure read 00087 float cur_encoder; // last encoder value read 00088 00089 float cur_position; // last position read 00090 00091 ArtBrakeModel *sim; // brake simulation model 00092 00093 // pointer to any of the private query_* methods 00094 typedef int (devbrake::*query_method_t)(float *); 00095 00096 // query methods 00097 int query_amps(float *data); 00098 int query_encoder(float *data); 00099 int query_pot(float *data); 00100 int query_pressure(float *data); 00101 int query_volts(float *data); 00102 00103 int calibrate_brake(void); 00104 void check_encoder_limits(void); 00105 int configure_brake(void); 00106 int encoder_goto(int enc_delta); 00107 int query_cmd(const char *string, char *status, int nbytes); 00108 int read_stable_value(query_method_t query_method, 00109 double *status, float epsilon); 00110 int servo_cmd(const char *string); 00111 void servo_write_only(const char *string); 00112 00113 // Convert encoder readings to and from float positions. 00114 inline float enc2pos(int encoder_val) 00115 {return ((encoder_val - encoder_min) / encoder_range);} 00116 inline int pos2enc(float position) /* simulation */ 00117 {return (int) rintf(encoder_min + position * encoder_range);} 00118 00119 // Convert potentiometer voltages to and from float positions. 00120 // Warning! pot_range is typically negative in these calculations. 00121 inline float pot2pos(float pot_volts) 00122 {return ((pot_volts - pot_off) / pot_range);} 00123 inline float pos2pot(float position) /* simulation */ 00124 {return position * pot_range + pot_off;} 00125 00126 // Convert pressure sensor voltages to and from float positions. 00127 inline float press2pos(float pressure_volts) 00128 {return ((pressure_volts - pressure_min) / pressure_range);} 00129 inline float pos2press(float position) /* simulation */ 00130 {return pressure_min + position * pressure_range;} 00131 }; 00132 00133 #if 0 00134 // limit position value to normal range 00135 static inline float limit_travel(float position) 00136 { 00137 if (position > 1.0) position = 1.0; 00138 else if (position < 0.0) position = 0.0; 00139 return position; 00140 } 00141 #endif 00142 00143 #endif // _DEVBRAKE_H_