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 
149 class BoschIMU:
157 {
158 protected:
159  bool verbose;
160  short status;
161  int nChannels;
167  double m_timeStamp;
168  double timeLastReport;
169  mutable std::mutex mutex;
170  bool i2c_flag;
171 
172  bool checkError;
173 
174  int fd;
177 
178  using ReadFuncPtr = bool (BoschIMU::*)(unsigned char, int, unsigned char*, std::string);
180 
181  unsigned char command[MAX_MSG_LENGTH];
182  unsigned char response[MAX_MSG_LENGTH];
183 
184 
185  bool checkWriteResponse(unsigned char *response);
186  bool checkReadResponse(unsigned char *response);
187 
188  void printBuffer(unsigned char *buffer, int length);
189  int readBytes(unsigned char *buffer, int bytes);
190  void dropGarbage();
191 
192  long int totMessagesRead;
195 
196  void readSysError();
197  // Serial
198  bool sendReadCommandSer(unsigned char register_add, int len, unsigned char* buf, std::string comment = "");
199  bool sendWriteCommandSer(unsigned char register_add, int len, unsigned char* cmd, std::string comment = "");
200  bool sendAndVerifyCommandSer(unsigned char register_add, int len, unsigned char* cmd, std::string comment);
201 
202  // i2c
203  bool sendReadCommandI2c(unsigned char register_add, int len, unsigned char* buf, std::string comment = "");
204 
205  int errs;
206  std::atomic<bool> dataIsValid;
207 
208 public:
209  BoschIMU();
210 
212 
218  bool open(yarp::os::Searchable& config) override;
219 
224  bool close() override;
225 
231  bool read(yarp::sig::Vector &out) override;
232 
238  bool getChannels(int *nc) override;
239 
246  bool calibrate(int ch, double v) override;
247 
248  /* IThreeAxisGyroscopes methods */
253  size_t getNrOfThreeAxisGyroscopes() const override;
254 
260  yarp::dev::MAS_status getThreeAxisGyroscopeStatus(size_t sens_index) const override;
261 
268  bool getThreeAxisGyroscopeName(size_t sens_index, std::string &name) const override;
269 
276  bool getThreeAxisGyroscopeFrameName(size_t sens_index, std::string &frameName) const override;
277 
285  bool getThreeAxisGyroscopeMeasure(size_t sens_index, yarp::sig::Vector& out, double& timestamp) const override;
286 
287  /* IThreeAxisLinearAccelerometers methods */
292  size_t getNrOfThreeAxisLinearAccelerometers() const override;
293 
299  yarp::dev::MAS_status getThreeAxisLinearAccelerometerStatus(size_t sens_index) const override;
300 
307  bool getThreeAxisLinearAccelerometerName(size_t sens_index, std::string &name) const override;
308 
315  bool getThreeAxisLinearAccelerometerFrameName(size_t sens_index, std::string &frameName) const override;
316 
324  bool getThreeAxisLinearAccelerometerMeasure(size_t sens_index, yarp::sig::Vector& out, double& timestamp) const override;
325 
326  /* IThreeAxisMagnetometers methods */
331  size_t getNrOfThreeAxisMagnetometers() const override;
332 
338  yarp::dev::MAS_status getThreeAxisMagnetometerStatus(size_t sens_index) const override;
339 
346  bool getThreeAxisMagnetometerName(size_t sens_index, std::string &name) const override;
347 
354  bool getThreeAxisMagnetometerFrameName(size_t sens_index, std::string &frameName) const override;
355 
363  bool getThreeAxisMagnetometerMeasure(size_t sens_index, yarp::sig::Vector& out, double& timestamp) const override;
364 
365  /* IOrientationSensors methods */
370  size_t getNrOfOrientationSensors() const override;
371 
377  yarp::dev::MAS_status getOrientationSensorStatus(size_t sens_index) const override;
378 
385  bool getOrientationSensorName(size_t sens_index, std::string &name) const override;
386 
393  bool getOrientationSensorFrameName(size_t sens_index, std::string &frameName) const override;
394 
402  bool getOrientationSensorMeasureAsRollPitchYaw(size_t sens_index, yarp::sig::Vector& rpy, double& timestamp) const override;
403 
408  bool threadInit() override;
409 
410 
414  void threadRelease() override;
415 
419  void run() override;
420 
421 private:
422  yarp::dev::MAS_status genericGetStatus(size_t sens_index) const;
423  bool genericGetSensorName(size_t sens_index, std::string &name) const;
424  bool genericGetFrameName(size_t sens_index, std::string &frameName) const;
425 
426  std::string m_sensorName;
427  std::string m_frameName;
428 };
429 
430 
431 #endif // BOSCH_IMU_DEVICE
BoschIMU::getNrOfOrientationSensors
size_t getNrOfOrientationSensors() const override
Get the number of orientation sensors in the device.
Definition: imuBosch_BNO055.cpp:864
BoschIMU::data_tmp
yarp::sig::Vector data_tmp
sensor data temporary buffer
Definition: imuBosch_BNO055.h:163
BoschIMU::getOrientationSensorStatus
yarp::dev::MAS_status getOrientationSensorStatus(size_t sens_index) const override
Get the status of orientation sensor.
Definition: imuBosch_BNO055.cpp:869
BoschIMU::sendWriteCommandSer
bool sendWriteCommandSer(unsigned char register_add, int len, unsigned char *cmd, std::string comment="")
Definition: imuBosch_BNO055.cpp:340
BoschIMU::getNrOfThreeAxisLinearAccelerometers
size_t getNrOfThreeAxisLinearAccelerometers() const override
Get the number of three axis linear accelerometers in the device.
Definition: imuBosch_BNO055.cpp:785
BoschIMU::close
bool close() override
Close the device.
Definition: imuBosch_BNO055.cpp:215
yarp::dev::IGenericSensor
A generic interface to sensors – gyro, a/d converters etc.
Definition: IGenericSensor.h:25
BoschIMU::getChannels
bool getChannels(int *nc) override
Get the number of channels of the sensor.
Definition: imuBosch_BNO055.cpp:733
yarp::os::Searchable
A base class for nested structures that can be searched.
Definition: Searchable.h:69
BoschIMU::errs
int errs
Definition: imuBosch_BNO055.h:205
Vector.h
contains the definition of a Vector type
BoschIMU::rf
yarp::os::ResourceFinder rf
resource finder object to load config parameters
Definition: imuBosch_BNO055.h:176
BoschIMU::threadInit
bool threadInit() override
Initialize process with desired device configurations.
Definition: imuBosch_BNO055.cpp:456
yarp::dev::DeviceDriver
Interface implemented by all device drivers.
Definition: DeviceDriver.h:38
BoschIMU::getThreeAxisMagnetometerFrameName
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.
Definition: imuBosch_BNO055.cpp:917
BoschIMU::quaternion
yarp::math::Quaternion quaternion
orientation in quaternion representation
Definition: imuBosch_BNO055.h:164
BoschIMU::calibrate
bool calibrate(int ch, double v) override
Calibrate the sensor, single channel.
Definition: imuBosch_BNO055.cpp:739
BoschIMU::getThreeAxisMagnetometerStatus
yarp::dev::MAS_status getThreeAxisMagnetometerStatus(size_t sens_index) const override
Get the status of three axis magnetometer.
Definition: imuBosch_BNO055.cpp:907
yarp::dev::IThreeAxisMagnetometers
Device interface to one or multiple three axis magnetometers.
Definition: MultipleAnalogSensorsInterfaces.h:165
BoschIMU::read
bool read(yarp::sig::Vector &out) override
Read a vector from the sensor.
Definition: imuBosch_BNO055.cpp:715
BoschIMU::readSysError
void readSysError()
Definition: imuBosch_BNO055.cpp:412
yarp::dev::IThreeAxisGyroscopes
Device interface to one or multiple three axis gyroscopes.
Definition: MultipleAnalogSensorsInterfaces.h:64
yarp::dev::IOrientationSensors
Device interface to one or multiple orientation sensors, such as IMUs with on board estimation algori...
Definition: MultipleAnalogSensorsInterfaces.h:274
BoschIMU::totMessagesRead
long int totMessagesRead
Definition: imuBosch_BNO055.h:192
BoschIMU::verbose
bool verbose
Flag to get verbose output.
Definition: imuBosch_BNO055.h:159
BoschIMU::getThreeAxisLinearAccelerometerMeasure
bool getThreeAxisLinearAccelerometerMeasure(size_t sens_index, yarp::sig::Vector &out, double &timestamp) const override
Get three axis linear accelerometer measurements.
Definition: imuBosch_BNO055.cpp:806
MultipleAnalogSensorsInterfaces.h
BoschIMU::getThreeAxisLinearAccelerometerStatus
yarp::dev::MAS_status getThreeAxisLinearAccelerometerStatus(size_t sens_index) const override
Get the status of three axis linear accelerometer.
Definition: imuBosch_BNO055.cpp:791
BoschIMU::i2c_flag
bool i2c_flag
flag to check if device connected through i2c commununication
Definition: imuBosch_BNO055.h:170
BoschIMU::BoschIMU
BoschIMU()
Definition: imuBosch_BNO055.cpp:61
Quaternion.h
BoschIMU::getThreeAxisGyroscopeMeasure
bool getThreeAxisGyroscopeMeasure(size_t sens_index, yarp::sig::Vector &out, double &timestamp) const override
Get three axis gyroscope measurements.
Definition: imuBosch_BNO055.cpp:846
BoschIMU::sendReadCommandI2c
bool sendReadCommandI2c(unsigned char register_add, int len, unsigned char *buf, std::string comment="")
Definition: imuBosch_BNO055.cpp:446
BoschIMU::~BoschIMU
~BoschIMU()
BoschIMU::fd
int fd
file descriptor to open device at system level
Definition: imuBosch_BNO055.h:174
BoschIMU
imuBosch_BNO055: This device will connect to the proper analogServer and read the data broadcasted ma...
Definition: imuBosch_BNO055.h:157
BoschIMU::errorCounter
yarp::sig::Vector errorCounter
Definition: imuBosch_BNO055.h:193
yarp::sig::VectorOf< double >
BoschIMU::ReadFuncPtr
bool(BoschIMU::*)(unsigned char, int, unsigned char *, std::string) ReadFuncPtr
Functor to choose between i2c or serial comm.
Definition: imuBosch_BNO055.h:178
BoschIMU::getThreeAxisLinearAccelerometerFrameName
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.
Definition: imuBosch_BNO055.cpp:801
BoschIMU::RPY_angle
yarp::sig::Vector RPY_angle
orientation in Euler angle representation
Definition: imuBosch_BNO055.h:166
BoschIMU::checkWriteResponse
bool checkWriteResponse(unsigned char *response)
Definition: imuBosch_BNO055.cpp:252
BoschIMU::getThreeAxisLinearAccelerometerName
bool getThreeAxisLinearAccelerometerName(size_t sens_index, std::string &name) const override
Get the name of three axis linear accelerometer.
Definition: imuBosch_BNO055.cpp:796
PolyDriver.h
BoschIMU::getThreeAxisGyroscopeName
bool getThreeAxisGyroscopeName(size_t sens_index, std::string &name) const override
Get the name of three axis gyroscope.
Definition: imuBosch_BNO055.cpp:836
MAX_MSG_LENGTH
constexpr int MAX_MSG_LENGTH
Definition: imuBosch_BNO055.h:64
yarp::dev::IThreeAxisLinearAccelerometers
Device interface to one or multiple three axis linear accelerometers.
Definition: MultipleAnalogSensorsInterfaces.h:118
BoschIMU::dataIsValid
std::atomic< bool > dataIsValid
Definition: imuBosch_BNO055.h:206
BoschIMU::nChannels
int nChannels
number of channels in the output port. Default 12. If 16, also includes quaternion data
Definition: imuBosch_BNO055.h:161
buffer
Definition: V4L_camera.h:75
BoschIMU::mutex
std::mutex mutex
mutex to avoid resource clash
Definition: imuBosch_BNO055.h:169
BoschIMU::status
short status
device status - UNUSED
Definition: imuBosch_BNO055.h:160
BoschIMU::m_timeStamp
double m_timeStamp
device timestamp
Definition: imuBosch_BNO055.h:167
yarp::math::Quaternion
Definition: Quaternion.h:27
BoschIMU::quaternion_tmp
yarp::math::Quaternion quaternion_tmp
orientation in quaternion representation
Definition: imuBosch_BNO055.h:165
BoschIMU::sendReadCommandSer
bool sendReadCommandSer(unsigned char register_add, int len, unsigned char *buf, std::string comment="")
Definition: imuBosch_BNO055.cpp:280
BoschIMU::checkReadResponse
bool checkReadResponse(unsigned char *response)
Definition: imuBosch_BNO055.cpp:223
ISerialDevice.h
BoschIMU::responseOffset
size_t responseOffset
Definition: imuBosch_BNO055.h:175
BoschIMU::printBuffer
void printBuffer(unsigned char *buffer, int length)
Definition: imuBosch_BNO055.cpp:405
yarp::os::PeriodicThread
An abstraction for a periodic thread.
Definition: PeriodicThread.h:25
BoschIMU::open
bool open(yarp::os::Searchable &config) override
Open the device and set up parameters/communication.
Definition: imuBosch_BNO055.cpp:87
BoschIMU::checkError
bool checkError
flag to check read error of sensor data
Definition: imuBosch_BNO055.h:172
BoschIMU::errorReading
yarp::sig::Vector errorReading
Definition: imuBosch_BNO055.h:194
PeriodicThread.h
BoschIMU::readFunc
ReadFuncPtr readFunc
Functor object.
Definition: imuBosch_BNO055.h:179
BoschIMU::timeLastReport
double timeLastReport
timestamp of last reported data
Definition: imuBosch_BNO055.h:168
BoschIMU::readBytes
int readBytes(unsigned char *buffer, int bytes)
Definition: imuBosch_BNO055.cpp:380
BoschIMU::sendAndVerifyCommandSer
bool sendAndVerifyCommandSer(unsigned char register_add, int len, unsigned char *cmd, std::string comment)
Definition: imuBosch_BNO055.cpp:433
BoschIMU::getOrientationSensorMeasureAsRollPitchYaw
bool getOrientationSensorMeasureAsRollPitchYaw(size_t sens_index, yarp::sig::Vector &rpy, double &timestamp) const override
Get orientation sensor measurements.
Definition: imuBosch_BNO055.cpp:884
BoschIMU::getThreeAxisGyroscopeStatus
yarp::dev::MAS_status getThreeAxisGyroscopeStatus(size_t sens_index) const override
Get the status of three axis gyroscope.
Definition: imuBosch_BNO055.cpp:831
BoschIMU::getOrientationSensorFrameName
bool getOrientationSensorFrameName(size_t sens_index, std::string &frameName) const override
Get the name of the frame in which orientation sensor measurements are expressed.
Definition: imuBosch_BNO055.cpp:879
yarp::dev::MAS_status
MAS_status
Status of a given analog sensor exposed by a multiple analog sensors interface.
Definition: MultipleAnalogSensorsInterfaces.h:37
IGenericSensor.h
BoschIMU::getThreeAxisMagnetometerName
bool getThreeAxisMagnetometerName(size_t sens_index, std::string &name) const override
Get the name of three axis magnetometer.
Definition: imuBosch_BNO055.cpp:912
BoschIMU::getThreeAxisGyroscopeFrameName
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.
Definition: imuBosch_BNO055.cpp:841
BoschIMU::getNrOfThreeAxisMagnetometers
size_t getNrOfThreeAxisMagnetometers() const override
Get the number of three axis magnetometers in the device.
Definition: imuBosch_BNO055.cpp:902
BoschIMU::getThreeAxisMagnetometerMeasure
bool getThreeAxisMagnetometerMeasure(size_t sens_index, yarp::sig::Vector &out, double &timestamp) const override
Get three axis magnetometer measurements.
Definition: imuBosch_BNO055.cpp:922
BoschIMU::run
void run() override
Update loop where measurements are read from the device.
Definition: imuBosch_BNO055.cpp:620
BoschIMU::getNrOfThreeAxisGyroscopes
size_t getNrOfThreeAxisGyroscopes() const override
Get the number of three axis gyroscopes in the device.
Definition: imuBosch_BNO055.cpp:825
BoschIMU::command
unsigned char command[MAX_MSG_LENGTH]
packet to be written to the device
Definition: imuBosch_BNO055.h:181
BoschIMU::response
unsigned char response[MAX_MSG_LENGTH]
packet to be read from the device
Definition: imuBosch_BNO055.h:182
ResourceFinder.h
BoschIMU::data
yarp::sig::Vector data
sensor data buffer
Definition: imuBosch_BNO055.h:162
BoschIMU::threadRelease
void threadRelease() override
Terminate communication with the device and release the thread.
Definition: imuBosch_BNO055.cpp:942
BoschIMU::getOrientationSensorName
bool getOrientationSensorName(size_t sens_index, std::string &name) const override
Get the name of orientation sensor.
Definition: imuBosch_BNO055.cpp:874
yarp::os::ResourceFinder
Helper class for finding config files and other external resources.
Definition: ResourceFinder.h:33
BoschIMU::dropGarbage
void dropGarbage()
Definition: imuBosch_BNO055.cpp:395