YARP
Yet Another Robot Platform
imuBosch_BNO055.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2006-2020 Istituto Italiano di Tecnologia (IIT)
3  *
4  * This library is free software; you can redistribute it and/or
5  * modify it under the terms of the GNU Lesser General Public
6  * License as published by the Free Software Foundation; either
7  * version 2.1 of the License, or (at your option) any later version.
8  *
9  * This library is distributed in the hope that it will be useful,
10  * but WITHOUT ANY WARRANTY; without even the implied warranty of
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
12  * Lesser General Public License for more details.
13  *
14  * You should have received a copy of the GNU Lesser General Public
15  * License along with this library; if not, write to the Free Software
16  * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
17  */
18 
19 #ifndef BOSCH_IMU_DEVICE
20 #define BOSCH_IMU_DEVICE
21 
22 #include <atomic>
23 #include <yarp/sig/Vector.h>
24 #include <yarp/os/PeriodicThread.h>
25 #include <yarp/dev/PolyDriver.h>
26 #include <yarp/os/ResourceFinder.h>
27 #include <yarp/dev/ISerialDevice.h>
30 #include <yarp/math/Quaternion.h>
31 #include <mutex>
32 
33 
34 /* Serial protocol description
35  *
36  * Write operation on a register:
37  * | Byte 1 | Byte 2 | Byte 3 | Byte 4 | Byte 5 | ... | Byte (n+4) |
38  * | Start | Write | Reg Addr| Length | Data 1 | ... | Data n |
39  * | 0xAA | 0x00 | <...> | <...> | <...> | ... | <...> |
40  *
41  * Response to write command:
42  * | 0xEE | <code> |
43  * 0x01: Write_success
44  * all other values are errors ... TODO: improve doc
45  *
46  * Read operation on a register:
47  * | Byte 1 | Byte 2 | Byte 3 | Byte 4 |
48  * | Start | Read | Reg Addr| Length |
49  * | 0xAA | 0x01 | <...> | <...> |
50  *
51  * Response to a successful read command:
52  * | Byte 1 | Byte 2 | Byte 3 | ... | Byte (n+2) |
53  * | Resp | Length | Data 1 | ... | Data n |
54  * | 0xBB | <...> | <...> | ... | <...> |
55  *
56  * Response to a failed read command:
57  * | Byte 1 | Byte 2 |
58  * | Resp | Status |
59  * | 0xEE | <...> |
60  *
61  * Read error code: TODO
62  */
63 
64 constexpr int MAX_MSG_LENGTH = 128;
65 
66 // Commands
67 #define START_BYTE 0xAA
68 #define WRITE_CMD 0x00
69 #define READ_CMD 0x01
70 
71 // Responses
72 #define REPLY_HEAD 0xBB
73 #define ERROR_HEAD 0xEE
74 #define WRITE_SUCC 0x01
75 #define READ_FAIL 0x02
76 #define WRITE_FAIL 0x03
77 
78 // Error code
79 #define REGISTER_NOT_READY 0x07
80 
81 // Registers
82 // Page 0 // Device has 2 pages of registers
83 #define REG_CHIP_ID 0x00
84 #define REG_SW_VERSION 0x04 // 2 software revision bytes
85 #define REG_BOOTLOADER 0x06 // 1 byte bootloader version
86 #define REG_PAGE_ID 0x07 // page ID number
87 
88 #define REG_ACC_DATA 0x08 // 3*2 bytes: LSB first (LSB 0x08, MSB 0x09) for X
89 #define REG_MAGN_DATA 0x0E // 3*2 bytes: LSB first
90 #define REG_GYRO_DATA 0x14 // 3*2 bytes: LSB first
91 #define REG_RPY_DATA 0x1A // 3*2 bytes: LSB first (raw order is Yaw, Roll, Pitch)
92 #define REG_QUATERN_DATA 0x20 // 4*2 bytes: LSB first (raw order is w, x, y, z)
93 #define REG_GRAVITY 0x2E // Gravity Vector data
94 #define REG_CALIB_STATUS 0x35 // Check if sensors are calibrated, 2 bits each. SYS - GYRO - ACC - MAG. 3 means calibrated, 0 not calbrated
95 #define REG_SYS_CLK_STATUS 0x38 // only 1 last LSB
96 #define REG_SYS_STATUS 0x39
97 #define REG_SYS_ERR 0x3A
98 #define REG_UNIT_SEL 0x3B
99 #define REG_OP_MODE 0x3D
100 #define REG_POWER_MODE 0x3E
101 #define REG_SYS_TRIGGER 0x3F
102 
103 // Values
104 #define CONFIG_MODE 0x00
105 #define AMG_MODE 0x07
106 #define IMU_MODE 0x08
107 #define M4G_MODE 0x0A
108 #define NDOF_MODE 0x0C
109 
110 // Sys trigger values (in OR if more than one is to be activated)
111 #define TRIG_EXT_CLK_SEL 0x80 // 1 for external clock (if available), 0 for internal clock
112 #define TRIG_RESET_INT 0x40 // reset interrupts
113 #define TRIG_RESET_SYSTEM 0x20 // reset system
114 #define TRIG_SELF_TEST 0x01 // Start self test
115 
116 #define BNO055_ID 0xA0
117 
118 #define RESP_HEADER_SIZE 2
119 // Time to wait while switching to and from config_mode & any operation_mode
120 #define SWITCHING_TIME 0.020 // 20ms
121 #define TIME_REPORT_INTERVAL 30
122 //number of attempts of sending config command
123 #define ATTEMPTS_NUM_OF_SEND_CONFIG_CMD 3
124 
125 
126 
145 class BoschIMU:
153 {
154 protected:
155  bool verbose;
156  short status;
157  int nChannels;
163  double m_timeStamp;
164  double timeLastReport;
165  mutable std::mutex mutex;
166  bool i2c_flag;
167 
168  bool checkError;
169 
170  int fd;
173 
174  using ReadFuncPtr = bool (BoschIMU::*)(unsigned char, int, unsigned char*, std::string);
176 
177  unsigned char command[MAX_MSG_LENGTH];
178  unsigned char response[MAX_MSG_LENGTH];
179 
180 
181  bool checkWriteResponse(unsigned char *response);
182  bool checkReadResponse(unsigned char *response);
183 
184  void printBuffer(unsigned char *buffer, int length);
185  int readBytes(unsigned char *buffer, int bytes);
186  void dropGarbage();
187 
188  long int totMessagesRead;
191 
192  void readSysError();
193  // Serial
194  bool sendReadCommandSer(unsigned char register_add, int len, unsigned char* buf, std::string comment = "");
195  bool sendWriteCommandSer(unsigned char register_add, int len, unsigned char* cmd, std::string comment = "");
196  bool sendAndVerifyCommandSer(unsigned char register_add, int len, unsigned char* cmd, std::string comment);
197 
198  // i2c
199  bool sendReadCommandI2c(unsigned char register_add, int len, unsigned char* buf, std::string comment = "");
200 
201  int errs;
202  std::atomic<bool> dataIsValid;
203 
204 public:
205  BoschIMU();
206 
208 
214  bool open(yarp::os::Searchable& config) override;
215 
220  bool close() override;
221 
227  bool read(yarp::sig::Vector &out) override;
228 
234  bool getChannels(int *nc) override;
235 
242  bool calibrate(int ch, double v) override;
243 
244  /* IThreeAxisGyroscopes methods */
249  size_t getNrOfThreeAxisGyroscopes() const override;
250 
256  yarp::dev::MAS_status getThreeAxisGyroscopeStatus(size_t sens_index) const override;
257 
264  bool getThreeAxisGyroscopeName(size_t sens_index, std::string &name) const override;
265 
272  bool getThreeAxisGyroscopeFrameName(size_t sens_index, std::string &frameName) const override;
273 
281  bool getThreeAxisGyroscopeMeasure(size_t sens_index, yarp::sig::Vector& out, double& timestamp) const override;
282 
283  /* IThreeAxisLinearAccelerometers methods */
288  size_t getNrOfThreeAxisLinearAccelerometers() const override;
289 
295  yarp::dev::MAS_status getThreeAxisLinearAccelerometerStatus(size_t sens_index) const override;
296 
303  bool getThreeAxisLinearAccelerometerName(size_t sens_index, std::string &name) const override;
304 
311  bool getThreeAxisLinearAccelerometerFrameName(size_t sens_index, std::string &frameName) const override;
312 
320  bool getThreeAxisLinearAccelerometerMeasure(size_t sens_index, yarp::sig::Vector& out, double& timestamp) const override;
321 
322  /* IThreeAxisMagnetometers methods */
327  size_t getNrOfThreeAxisMagnetometers() const override;
328 
334  yarp::dev::MAS_status getThreeAxisMagnetometerStatus(size_t sens_index) const override;
335 
342  bool getThreeAxisMagnetometerName(size_t sens_index, std::string &name) const override;
343 
350  bool getThreeAxisMagnetometerFrameName(size_t sens_index, std::string &frameName) const override;
351 
359  bool getThreeAxisMagnetometerMeasure(size_t sens_index, yarp::sig::Vector& out, double& timestamp) const override;
360 
361  /* IOrientationSensors methods */
366  size_t getNrOfOrientationSensors() const override;
367 
373  yarp::dev::MAS_status getOrientationSensorStatus(size_t sens_index) const override;
374 
381  bool getOrientationSensorName(size_t sens_index, std::string &name) const override;
382 
389  bool getOrientationSensorFrameName(size_t sens_index, std::string &frameName) const override;
390 
398  bool getOrientationSensorMeasureAsRollPitchYaw(size_t sens_index, yarp::sig::Vector& rpy, double& timestamp) const override;
399 
404  bool threadInit() override;
405 
406 
410  void threadRelease() override;
411 
415  void run() override;
416 
417 private:
418  yarp::dev::MAS_status genericGetStatus(size_t sens_index) const;
419  bool genericGetSensorName(size_t sens_index, std::string &name) const;
420  bool genericGetFrameName(size_t sens_index, std::string &frameName) const;
421 
422  std::string m_sensorName;
423  std::string m_frameName;
424 };
425 
426 
427 #endif // BOSCH_IMU_DEVICE
contains the definition of a Vector type
void threadRelease() override
Terminate communication with the device and release the thread.
yarp::sig::Vector errorReading
unsigned char command[MAX_MSG_LENGTH]
packet to be written to the device
bool getThreeAxisGyroscopeMeasure(size_t sens_index, yarp::sig::Vector &out, double &timestamp) const override
Get three axis gyroscope measurements.
bool sendReadCommandSer(unsigned char register_add, int len, unsigned char *buf, std::string comment="")
std::atomic< bool > dataIsValid
std::mutex mutex
mutex to avoid resource clash
short status
device status - UNUSED
size_t responseOffset
bool checkReadResponse(unsigned char *response)
ReadFuncPtr readFunc
Functor object.
yarp::math::Quaternion quaternion_tmp
orientation in quaternion representation
size_t getNrOfThreeAxisMagnetometers() const override
Get the number of three axis magnetometers in the device.
void printBuffer(unsigned char *buffer, int length)
bool checkError
flag to check read error of sensor data
yarp::sig::Vector data
sensor data buffer
yarp::os::ResourceFinder rf
resource finder object to load config parameters
bool getChannels(int *nc) override
Get the number of channels of the sensor.
bool sendReadCommandI2c(unsigned char register_add, int len, unsigned char *buf, std::string comment="")
bool getThreeAxisLinearAccelerometerFrameName(size_t sens_index, std::string &frameName) const override
Get the name of the frame in which three axis linear accelerometer measurements are expressed.
bool getThreeAxisGyroscopeFrameName(size_t sens_index, std::string &frameName) const override
Get the name of the frame in which three axis gyroscope measurements are expressed.
bool close() override
Close the device.
bool i2c_flag
flag to check if device connected through i2c commununication
double m_timeStamp
device timestamp
unsigned char response[MAX_MSG_LENGTH]
packet to be read from the device
bool getOrientationSensorFrameName(size_t sens_index, std::string &frameName) const override
Get the name of the frame in which orientation sensor measurements are expressed.
void dropGarbage()
bool threadInit() override
Initialize process with desired device configurations.
long int totMessagesRead
bool verbose
Flag to get verbose output.
bool sendAndVerifyCommandSer(unsigned char register_add, int len, unsigned char *cmd, std::string comment)
bool getThreeAxisGyroscopeName(size_t sens_index, std::string &name) const override
Get the name of three axis gyroscope.
bool getOrientationSensorMeasureAsRollPitchYaw(size_t sens_index, yarp::sig::Vector &rpy, double &timestamp) const override
Get orientation sensor measurements.
bool checkWriteResponse(unsigned char *response)
bool calibrate(int ch, double v) override
Calibrate the sensor, single channel.
yarp::sig::Vector errorCounter
bool getThreeAxisMagnetometerFrameName(size_t sens_index, std::string &frameName) const override
Get the name of the frame in which three axis magnetometer measurements are expressed.
int nChannels
number of channels in the output port. Default 12. If 16, also includes quaternion data
yarp::dev::MAS_status getOrientationSensorStatus(size_t sens_index) const override
Get the status of orientation sensor.
bool getThreeAxisLinearAccelerometerName(size_t sens_index, std::string &name) const override
Get the name of three axis linear accelerometer.
bool read(yarp::sig::Vector &out) override
Read a vector from the sensor.
bool getOrientationSensorName(size_t sens_index, std::string &name) const override
Get the name of orientation sensor.
void readSysError()
yarp::dev::MAS_status getThreeAxisGyroscopeStatus(size_t sens_index) const override
Get the status of three axis gyroscope.
bool getThreeAxisMagnetometerName(size_t sens_index, std::string &name) const override
Get the name of three axis magnetometer.
yarp::math::Quaternion quaternion
orientation in quaternion representation
bool sendWriteCommandSer(unsigned char register_add, int len, unsigned char *cmd, std::string comment="")
yarp::dev::MAS_status getThreeAxisMagnetometerStatus(size_t sens_index) const override
Get the status of three axis magnetometer.
double timeLastReport
timestamp of last reported data
int readBytes(unsigned char *buffer, int bytes)
size_t getNrOfThreeAxisGyroscopes() const override
Get the number of three axis gyroscopes in the device.
int fd
file descriptor to open device at system level
size_t getNrOfThreeAxisLinearAccelerometers() const override
Get the number of three axis linear accelerometers in the device.
bool open(yarp::os::Searchable &config) override
Open the device and set up parameters/communication.
yarp::sig::Vector data_tmp
sensor data temporary buffer
size_t getNrOfOrientationSensors() const override
Get the number of orientation sensors in the device.
bool getThreeAxisLinearAccelerometerMeasure(size_t sens_index, yarp::sig::Vector &out, double &timestamp) const override
Get three axis linear accelerometer measurements.
yarp::sig::Vector RPY_angle
orientation in Euler angle representation
bool(BoschIMU::*)(unsigned char, int, unsigned char *, std::string) ReadFuncPtr
Functor to choose between i2c or serial comm.
yarp::dev::MAS_status getThreeAxisLinearAccelerometerStatus(size_t sens_index) const override
Get the status of three axis linear accelerometer.
bool getThreeAxisMagnetometerMeasure(size_t sens_index, yarp::sig::Vector &out, double &timestamp) const override
Get three axis magnetometer measurements.
void run() override
Update loop where measurements are read from the device.
Interface implemented by all device drivers.
Definition: DeviceDriver.h:38
A generic interface to sensors – gyro, a/d converters etc.
Device interface to one or multiple orientation sensors, such as IMUs with on board estimation algori...
Device interface to one or multiple three axis gyroscopes.
Device interface to one or multiple three axis linear accelerometers.
Device interface to one or multiple three axis magnetometers.
An abstraction for a periodic thread.
Helper class for finding config files and other external resources.
A base class for nested structures that can be searched.
Definition: Searchable.h:69
constexpr int MAX_MSG_LENGTH
MAS_status
Status of a given analog sensor exposed by a multiple analog sensors interface.