Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040 #ifndef PROXIMITY_SENSOR_DRIVER_H__
00041 #define PROXIMITY_SENSOR_DRIVER_H__
00042
00043
00044 #include <libsub.h>
00045
00046 #include "proximity_sensor_driver/prox_sensor_measurement.h"
00047 #include "proximity_sensor_driver/proximity_sensor_measurement.h"
00048 #include "proximity_sensor_driver/reinitialize_proximity_sensor.h"
00049
00050
00051 #include <dynamic_reconfigure/server.h>
00052 #include <proximity_sensor_driver/ProximitySensorConfig.h>
00053
00062 class ProxSensor
00063 {
00064 public:
00075 ProxSensor( const ros::NodeHandle& nh );
00076
00080 ~ProxSensor();
00081
00099 bool getMeasurement( void );
00100
00101 void checkConnection( void );
00102
00104 void reconfigure_callback( proximity_sensor_driver::ProximitySensorConfig &config, uint32_t level );
00105 bool reinitialize_callback( proximity_sensor_driver::reinitialize_proximity_sensor::Request &req,
00106 proximity_sensor_driver::reinitialize_proximity_sensor::Response &res );
00107
00108
00109
00110 enum skin_cell_shape { SQUARE, RECTANGLE, TRIANGLE };
00111 struct skin_cell
00112 {
00113 uint8_t status;
00114 uint8_t value;
00115 uint8_t offset;
00116 uint8_t limit;
00117 uint8_t U1;
00118 uint8_t U2;
00119 uint8_t U3;
00120 uint8_t dynamic;
00121 };
00122 enum ECU_command { INITIALIZE = 1, WRITE_TO_FLASH = 2, SET_DYNAMIC_THRESHOLD = 3, SET_STATIC_THRESHOLD = 4, SET_END_OF_CHAIN = 5, ACTIVATE_SENSOR = 6, DEACTIVATE_SENSOR = 7 };
00123 enum sensor_activity { ACTIVE = (char)1, INACTIVE = (char)0 };
00124
00125
00126
00128 static const int PROX_SENSOR_I2C_ADR = 0x01;
00129
00130 static const int RAM_ADR_LENGTH = 2;
00131 static const int RAM_WRITE_LENGTH = 1;
00133 static const uint8_t SKIP_MEM_ADR_WRITE = 0;
00134
00135
00137 static const uint16_t COMMAND_ADR = 0x00C0;
00139 static const uint16_t DYNAMIC_THRESHOLD_ADR = 0x00C2;
00141 static const uint16_t STATIC_THRESHOLD_ADR = 0x0103;
00143 static const uint16_t ACTIVATE_ADR = 0x0100;
00145 static const uint8_t DATA_ADR_HI = 0x01;
00147 static const uint8_t DATA_ADR_LO = 0x00;
00149 static const uint8_t STATUS_ADDRESS_HIGH = 0x00;
00151 static const uint8_t STATUS_ADDRESS_LOW = 0xC1;
00153 static const uint8_t STATUS_LENGTH = 2;
00154
00155
00157 static const int MAX_SENSORS = 192;
00159 static const int MAX_BYTES_PER_I2C = 256;
00161 static const int SENSORS_PER_I2C = MAX_BYTES_PER_I2C / sizeof(struct skin_cell);
00163 static const uint8_t END_OF_CHAIN_MARKER = 254;
00165 static const uint8_t THRESHOLD_DEFAULT = 10;
00166
00167
00168
00169
00171 sub_handle handle_;
00172 sub_device subdev_;
00174 bool skin_connected_;
00175
00176 std::string serialNumber_;
00177
00178 sub_int32_t i2c_frequency_;
00179
00180
00181
00182
00184 struct skin_cell cells_[MAX_SENSORS];
00186 skin_cell_shape shapes_[MAX_SENSORS];
00188 int cell_count_;
00190 uint8_t noise_;
00192 uint8_t threshold_;
00194 uint8_t dynamic_threshold_;
00195
00197
00199
00200
00201
00202 bool status_go_;
00203 bool status_err_;
00204
00205 bool init( void );
00206
00207 bool sendToECU( ECU_command command, uint8_t sensor_number, uint8_t data );
00208
00218
00219
00220 };
00221
00222
00223 #endif // PROXIMITY_SENSOR_DRIVER_H__