Communitcates with the Bosch sensor skin. More...
#include <proximity_sensor_driver.h>
Classes | |
struct | skin_cell |
Public Types | |
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 } |
enum | sensor_activity { ACTIVE = (char)1, INACTIVE = (char)0 } |
enum | skin_cell_shape { SQUARE, RECTANGLE, TRIANGLE } |
Public Member Functions | |
void | checkConnection (void) |
bool | getMeasurement (void) |
bool | init (void) |
ProxSensor (const ros::NodeHandle &nh) | |
void | reconfigure_callback (proximity_sensor_driver::ProximitySensorConfig &config, uint32_t level) |
Dynamic reconfigure callback. | |
bool | reinitialize_callback (proximity_sensor_driver::reinitialize_proximity_sensor::Request &req, proximity_sensor_driver::reinitialize_proximity_sensor::Response &res) |
bool | sendToECU (ECU_command command, uint8_t sensor_number, uint8_t data) |
~ProxSensor () | |
Reset values and to close the opened Sub20 device. | |
Public Attributes | |
int | cell_count_ |
Number of sensor elements connected to the ECU of the sensor skin. | |
struct skin_cell | cells_ [MAX_SENSORS] |
Array containing measurements for each cell. | |
uint8_t | dynamic_threshold_ |
Value of dynamic threshold. | |
sub_handle | handle_ |
device handle | |
sub_int32_t | i2c_frequency_ |
uint8_t | noise_ |
Noise threshold in sensor readings. | |
std::string | serialNumber_ |
skin_cell_shape | shapes_ [MAX_SENSORS] |
Array containing shape of each cell. | |
bool | skin_connected_ |
skin connection state | |
bool | status_err_ |
bool | status_go_ |
skin initialization state | |
sub_device | subdev_ |
uint8_t | threshold_ |
Obstacle detection threshold. | |
Static Public Attributes | |
static const uint16_t | ACTIVATE_ADR = 0x0100 |
Address of of the bit for activating the first sensor. | |
static const uint16_t | COMMAND_ADR = 0x00C0 |
Address for command bytes sent to ECU RAM. | |
static const uint8_t | DATA_ADR_HI = 0x01 |
High byte of the beginning address of the sensor data in ECU RAM. | |
static const uint8_t | DATA_ADR_LO = 0x00 |
Low byte of the beginning address of the sensor data in ECU RAM. | |
static const uint16_t | DYNAMIC_THRESHOLD_ADR = 0x00C2 |
Address of the dynamic threshold in the ECU RAM. | |
static const uint8_t | END_OF_CHAIN_MARKER = 254 |
Value of the end of chain marker. | |
static const int | MAX_BYTES_PER_I2C = 256 |
Maximum number of bytes which can be read over a single I2C transmission. | |
static const int | MAX_SENSORS = 192 |
Maximum number of connectable sensors. | |
static const int | PROX_SENSOR_I2C_ADR = 0x01 |
Address of slave (sensor skin) | |
static const int | RAM_ADR_LENGTH = 2 |
static const int | RAM_WRITE_LENGTH = 1 |
static const int | SENSORS_PER_I2C = MAX_BYTES_PER_I2C / sizeof(struct skin_cell) |
The number of sensors which can be queried in a single I2C transmission. | |
static const uint8_t | SKIP_MEM_ADR_WRITE = 0 |
Give this value for 'ma_sz' in sub_i2c_read/sub_i2c_write to skip the "Memory Address Write" stage. | |
static const uint16_t | STATIC_THRESHOLD_ADR = 0x0103 |
Address of the static threshold of the first cell in the ECU RAM. | |
static const uint8_t | STATUS_ADDRESS_HIGH = 0x00 |
High byte of the beginning address of the status data in ECU RAM. | |
static const uint8_t | STATUS_ADDRESS_LOW = 0xC1 |
Low byte of the beginning address of the status data in ECU RAM. | |
static const uint8_t | STATUS_LENGTH = 2 |
Length of status message in bytes. | |
static const uint8_t | THRESHOLD_DEFAULT = 10 |
Default value for thresholds if not set by parameters in yaml file. |
Communitcates with the Bosch sensor skin.
The class ProxSensor handles the communication with the sensor skin and the GUIs. It reads the sensor values as well as the log files from the sensor skin and publishes them on the topic "skin_data". Apart from that the class also writes data in the ECU of the skin when a service request is sent.
Definition at line 62 of file proximity_sensor_driver.h.
INITIALIZE | |
WRITE_TO_FLASH | |
SET_DYNAMIC_THRESHOLD | |
SET_STATIC_THRESHOLD | |
SET_END_OF_CHAIN | |
ACTIVATE_SENSOR | |
DEACTIVATE_SENSOR |
Definition at line 122 of file proximity_sensor_driver.h.
Definition at line 123 of file proximity_sensor_driver.h.
Definition at line 110 of file proximity_sensor_driver.h.
ProxSensor::ProxSensor | ( | const ros::NodeHandle & | nh | ) |
The constructor of the scans all connected USB devices and looks for a Sub20 device with connection to a sensor skin. If a Sub20 device with a connection to a sensor skin is found the number of connected sensor elements will be determined. To determine the number of sensor elements the constructor reads the value "Limit" of each sensor element until the end of chain marker (Limit == 254) is found. This marker is an indicator for the first unused sensor element address.
Definition at line 60 of file proximity_sensor_driver.cpp.
Reset values and to close the opened Sub20 device.
Definition at line 104 of file proximity_sensor_driver.cpp.
void ProxSensor::checkConnection | ( | void | ) |
Definition at line 359 of file proximity_sensor_driver.cpp.
bool ProxSensor::getMeasurement | ( | void | ) |
Get the most recent measurement from all skin cells
The function "GetOneMeas" reads the data of the connected sensor elements as well as the log files from the RAM of the sensor skin.
To read data from the RAM of the sensor skin a special communication pattern has to be used.
Communication pattern: 1.) Memory address write Start|Slave Adr. (Bit1-7) + Bit0 = 0|Mem. Addr. MSB|Mem. Addr. LSB|Stop
2.) Wait for 50ms
3.) Data read Start|Slave Adr. (Bit1-7) + Bit0 = 1|Data[0]|Data[1]|... |Stop
Definition at line 266 of file proximity_sensor_driver.cpp.
bool ProxSensor::init | ( | void | ) |
Definition at line 116 of file proximity_sensor_driver.cpp.
void ProxSensor::reconfigure_callback | ( | proximity_sensor_driver::ProximitySensorConfig & | config, |
uint32_t | level | ||
) |
Dynamic reconfigure callback.
Definition at line 456 of file proximity_sensor_driver.cpp.
bool ProxSensor::reinitialize_callback | ( | proximity_sensor_driver::reinitialize_proximity_sensor::Request & | req, |
proximity_sensor_driver::reinitialize_proximity_sensor::Response & | res | ||
) |
Definition at line 528 of file proximity_sensor_driver.cpp.
bool ProxSensor::sendToECU | ( | ECU_command | command, |
uint8_t | sensor_number, | ||
uint8_t | data | ||
) |
Definition at line 369 of file proximity_sensor_driver.cpp.
const uint16_t ProxSensor::ACTIVATE_ADR = 0x0100 [static] |
Address of of the bit for activating the first sensor.
Definition at line 143 of file proximity_sensor_driver.h.
Number of sensor elements connected to the ECU of the sensor skin.
Definition at line 188 of file proximity_sensor_driver.h.
struct skin_cell ProxSensor::cells_[MAX_SENSORS] |
Array containing measurements for each cell.
Definition at line 184 of file proximity_sensor_driver.h.
const uint16_t ProxSensor::COMMAND_ADR = 0x00C0 [static] |
Address for command bytes sent to ECU RAM.
Definition at line 137 of file proximity_sensor_driver.h.
const uint8_t ProxSensor::DATA_ADR_HI = 0x01 [static] |
High byte of the beginning address of the sensor data in ECU RAM.
Definition at line 145 of file proximity_sensor_driver.h.
const uint8_t ProxSensor::DATA_ADR_LO = 0x00 [static] |
Low byte of the beginning address of the sensor data in ECU RAM.
Definition at line 147 of file proximity_sensor_driver.h.
uint8_t ProxSensor::dynamic_threshold_ |
Value of dynamic threshold.
Definition at line 194 of file proximity_sensor_driver.h.
const uint16_t ProxSensor::DYNAMIC_THRESHOLD_ADR = 0x00C2 [static] |
Address of the dynamic threshold in the ECU RAM.
Definition at line 139 of file proximity_sensor_driver.h.
const uint8_t ProxSensor::END_OF_CHAIN_MARKER = 254 [static] |
Value of the end of chain marker.
Definition at line 163 of file proximity_sensor_driver.h.
sub_handle ProxSensor::handle_ |
device handle
Definition at line 171 of file proximity_sensor_driver.h.
sub_int32_t ProxSensor::i2c_frequency_ |
Definition at line 178 of file proximity_sensor_driver.h.
const int ProxSensor::MAX_BYTES_PER_I2C = 256 [static] |
Maximum number of bytes which can be read over a single I2C transmission.
Definition at line 159 of file proximity_sensor_driver.h.
const int ProxSensor::MAX_SENSORS = 192 [static] |
Maximum number of connectable sensors.
Definition at line 157 of file proximity_sensor_driver.h.
uint8_t ProxSensor::noise_ |
Noise threshold in sensor readings.
Definition at line 190 of file proximity_sensor_driver.h.
const int ProxSensor::PROX_SENSOR_I2C_ADR = 0x01 [static] |
Address of slave (sensor skin)
Definition at line 128 of file proximity_sensor_driver.h.
const int ProxSensor::RAM_ADR_LENGTH = 2 [static] |
Definition at line 130 of file proximity_sensor_driver.h.
const int ProxSensor::RAM_WRITE_LENGTH = 1 [static] |
Definition at line 131 of file proximity_sensor_driver.h.
const int ProxSensor::SENSORS_PER_I2C = MAX_BYTES_PER_I2C / sizeof(struct skin_cell) [static] |
The number of sensors which can be queried in a single I2C transmission.
Definition at line 161 of file proximity_sensor_driver.h.
std::string ProxSensor::serialNumber_ |
Definition at line 176 of file proximity_sensor_driver.h.
Array containing shape of each cell.
Definition at line 186 of file proximity_sensor_driver.h.
skin connection state
Definition at line 174 of file proximity_sensor_driver.h.
const uint8_t ProxSensor::SKIP_MEM_ADR_WRITE = 0 [static] |
Give this value for 'ma_sz' in sub_i2c_read/sub_i2c_write to skip the "Memory Address Write" stage.
Definition at line 133 of file proximity_sensor_driver.h.
const uint16_t ProxSensor::STATIC_THRESHOLD_ADR = 0x0103 [static] |
Address of the static threshold of the first cell in the ECU RAM.
Definition at line 141 of file proximity_sensor_driver.h.
const uint8_t ProxSensor::STATUS_ADDRESS_HIGH = 0x00 [static] |
High byte of the beginning address of the status data in ECU RAM.
Definition at line 149 of file proximity_sensor_driver.h.
const uint8_t ProxSensor::STATUS_ADDRESS_LOW = 0xC1 [static] |
Low byte of the beginning address of the status data in ECU RAM.
Definition at line 151 of file proximity_sensor_driver.h.
Definition at line 203 of file proximity_sensor_driver.h.
skin initialization state
This flag is true if a valid measurement is available
Definition at line 202 of file proximity_sensor_driver.h.
const uint8_t ProxSensor::STATUS_LENGTH = 2 [static] |
Length of status message in bytes.
Definition at line 153 of file proximity_sensor_driver.h.
sub_device ProxSensor::subdev_ |
Definition at line 172 of file proximity_sensor_driver.h.
uint8_t ProxSensor::threshold_ |
Obstacle detection threshold.
Definition at line 192 of file proximity_sensor_driver.h.
const uint8_t ProxSensor::THRESHOLD_DEFAULT = 10 [static] |
Default value for thresholds if not set by parameters in yaml file.
Definition at line 165 of file proximity_sensor_driver.h.