Joint Level Control
swing_sensor_rosinterface.h
Go to the documentation of this file.
1 #ifndef SWING_SENSOR_ROS
2 #define SWING_SENSOR_ROS
3 
4 #include <string>
10 //Error flags to diferentiate between errors
11 const uint8_t SPI_CMD_ERROR = 0x01;
12 const uint8_t SPI_PARITY_ERROR = 0x02;
13 const uint8_t SPI_DEVICE_ERROR = 0x04;
14 const uint8_t SPI_MODE_ERROR = 0x08;
15 const uint8_t ANGLE_OUT_OF_BOUNDS_ERROR = 0x10;
16 const uint8_t JOINT_LIMIT_ERROR = 0x20;
17 
28 uint16_t readSwingAngle(const std::string& spi_device, uint8_t spi_cs_id, uint8_t spi_mode, uint8_t spi_bits, uint32_t spi_speed, uint16_t spi_delay, uint8_t* error);
29 
30 #endif
uint16_t readSwingAngle(const std::string &spi_device, uint8_t spi_cs_id, uint8_t spi_mode, uint8_t spi_bits, uint32_t spi_speed, uint16_t spi_delay, uint8_t *error)
This function is responsible for reading data from the hall sensors over spi. Returns the Hallsensor ...
Definition: swing_sensor_rosinterface.cpp:44
const uint8_t SPI_PARITY_ERROR
flag if the parity of the spi msg is wrong
Definition: swing_sensor_rosinterface.h:12
const uint8_t ANGLE_OUT_OF_BOUNDS_ERROR
flag if the returned value is unfeasible
Definition: swing_sensor_rosinterface.h:15
const uint8_t SPI_DEVICE_ERROR
flag if the spi device can't be opened
Definition: swing_sensor_rosinterface.h:13
const uint8_t SPI_CMD_ERROR
flag if the cmd frame error bit in the spi msg is set
Definition: swing_sensor_rosinterface.h:11
const uint8_t SPI_MODE_ERROR
flag if the spi mode can't be set / read
Definition: swing_sensor_rosinterface.h:14
const uint8_t JOINT_LIMIT_ERROR
flag if the read angle is not within the joint limits
Definition: swing_sensor_rosinterface.h:16