19 #include <arpa/inet.h>
29 #include <linux/i2c-dev.h>
30 #ifdef I2C_HAS_SMBUS_H
32 # include <i2c/smbus.h>
35 #include <linux/kernel.h>
37 #include <sys/ioctl.h>
39 #include <sys/types.h>
56 constexpr uint8_t i2cAddrA = 0x28;
71 readFunc(&
BoschIMU::sendReadCommandSer),
80 errorCounter.resize(11);
90 yCTrace(IMUBOSCH_BNO055,
"Parameters are:\n\t%s", config.
toString().c_str());
92 if(!config.
check(
"comport") && !config.
check(
"i2c"))
94 yCError(IMUBOSCH_BNO055) <<
"Params 'comport' and 'i2c' not found";
98 if (config.
check(
"comport") && config.
check(
"i2c"))
100 yCError(IMUBOSCH_BNO055) <<
"Params 'comport' and 'i2c' both specified";
104 i2c_flag = config.
check(
"i2c");
110 responseOffset = i2c_flag ? 0 : 2;
116 yCError(IMUBOSCH_BNO055) <<
"i2c param malformed, it should be a string, aborting.";
121 fd = ::open(i2cDevFile.c_str(), O_RDWR);
125 yCError(IMUBOSCH_BNO055,
"Can't open %s, %s", i2cDevFile.c_str(), strerror(errno));
129 if (::ioctl(fd, I2C_SLAVE, i2cAddrA) < 0)
131 yCError(IMUBOSCH_BNO055,
"ioctl failed on %s, %s", i2cDevFile.c_str(), strerror(errno));
138 fd = ::open(config.
find(
"comport").
toString().c_str(), O_RDWR | O_NOCTTY );
140 yCError(IMUBOSCH_BNO055,
"Can't open %s, %s", config.
find(
"comport").
toString().c_str(), strerror(errno));
144 struct termios options;
145 tcgetattr(fd, &options);
150 int baudRate = B115200;
151 cfsetospeed(&options, baudRate);
152 cfsetispeed(&options, baudRate);
155 options.c_cflag &= ~CSIZE;
156 options.c_cflag |= CS8;
159 options.c_cflag &= ~CSTOPB;
162 options.c_cflag &=~PARENB;
170 options.c_cc[VMIN] = 0;
171 options.c_cc[VTIME] = 2;
174 options.c_cflag |= (CLOCAL | CREAD);
176 tcflush(fd, TCIOFLUSH);
179 if ( tcsetattr(fd, TCSANOW, &options) != 0)
181 yCError(IMUBOSCH_BNO055,
"Configuring comport failed");
187 nChannels = config.
check(
"channels",
Value(12)).asInt32();
189 double period = config.
check(
"period",
Value(10),
"Thread period in ms").asInt32() / 1000.0;
198 m_sensorName =
"sensor_imu_bosch_bno055";
199 yCWarning(IMUBOSCH_BNO055) <<
"Parameter \"sensor_name\" not set. Using default value \"" << m_sensorName <<
"\" for this parameter.";
208 m_frameName = m_sensorName;
209 yCWarning(IMUBOSCH_BNO055) <<
"Parameter \"frame_name\" not set. Using the same value as \"sensor_name\" for this parameter.";
212 return PeriodicThread::start();
219 PeriodicThread::stop();
235 "Inertial sensor didn't understand the command. \n\
236 If this error happens more than once in a row, please check serial communication is working fine and it isn't affected by electrical disturbance.");
238 errorCounter[response[1]]++;
245 "Received unknown response message. \n\
246 If this error happens more than once in a row, please check serial communication is working fine and it isn't affected by electrical disturbance.");
263 "Inertial sensor didn't understand the command. \n\
264 If this error happens more than once in a row, please check serial communication is working fine and it isn't affected by electrical disturbance.");
266 errorCounter[response[1]]++;
273 "Received unknown response message. \n\
274 If this error happens more than once in a row, please check serial communication is working fine and it isn't affected by electrical disturbance.");
288 bool success =
false;
289 for(
int trials=0; (trials<3) && (success==
false); trials++)
295 command[2]= register_add;
302 nbytes_w =
::write(fd, (
void*)command, command_len);
304 if(nbytes_w != command_len)
306 yCError(IMUBOSCH_BNO055) <<
"Cannot correctly send the message: " << comment;
311 memset(buf, 0x00, 20);
318 else if(!checkReadResponse(buf))
329 readBytes(&buf[2], (
int) buf[1]);
342 int command_len = 4+len;
347 command[2]= register_add;
348 command[3]= (
unsigned char) len;
349 for(
int i=0; i<len; i++)
350 command[4+i] = cmd[i];
356 nbytes_w =
::write(fd, (
void*)command, command_len);
357 if(nbytes_w != command_len)
359 yCError(IMUBOSCH_BNO055) <<
"Cannot correctly send the message: " << comment;
365 memset(response, 0x00, 20);
366 readBytes(response, 2);
367 if(!checkWriteResponse(response))
370 yCError(IMUBOSCH_BNO055) <<
"FAILED writing " << comment;
390 while(r!=0 && bytesRead < bytes);
398 while( (::
read(fd, (
void*) &
byte, 1) > 0 ))
407 for(
int i=0; i< length; i++)
408 printf(
"\t0x%02X ",
buffer[i]);
420 if(!sendReadCommandSer(
REG_SYS_STATUS, 1, response,
"Read SYS_STATUS register") )
422 yCError(IMUBOSCH_BNO055) <<
"@ line " << __LINE__;
425 if(!sendReadCommandSer(
REG_SYS_ERR, 1, response,
"Read SYS_ERR register") )
427 yCError(IMUBOSCH_BNO055) <<
"@ line " << __LINE__;
439 ret=sendWriteCommandSer(register_add, len, cmd, comment);
448 if (i2c_smbus_read_i2c_block_data(fd, register_add, len, buf) < 0)
450 yCError(IMUBOSCH_BNO055) <<
"Cannot correctly send the message: " << comment;
466 yCError(IMUBOSCH_BNO055) <<
"Wrong device on the bus, it is not BNO055";
479 yCError(IMUBOSCH_BNO055) <<
"Unable to set the Config mode";
487 yCError(IMUBOSCH_BNO055) <<
"Unable to set external clock";
496 if (i2c_smbus_write_byte_data(fd,
REG_PAGE_ID, 0x00) < 0)
498 yCError(IMUBOSCH_BNO055) <<
"Unable to set the page ID";
507 yCError(IMUBOSCH_BNO055) <<
"Unable to set the Operative mode";
519 if(!sendAndVerifyCommandSer(
REG_PAGE_ID, 1, &msg,
"PAGE_ID") )
521 yCError(IMUBOSCH_BNO055) <<
"Set page id 0 failed";
550 if(!sendAndVerifyCommandSer(
REG_OP_MODE, 1, &msg,
"Set config mode") )
552 yCError(IMUBOSCH_BNO055) <<
"Set config mode failed";
566 if(!sendAndVerifyCommandSer(
REG_SYS_TRIGGER, 1, &msg,
"Set external clock") )
568 yCError(IMUBOSCH_BNO055) <<
"Set external clock failed";
590 if(!sendAndVerifyCommandSer(
REG_OP_MODE, 1, &msg,
"Set config NDOF_MODE") )
592 yCError(IMUBOSCH_BNO055) <<
"Set config NDOF_MODE failed";
601 for(
int i=0; i<10; i++)
613 yCError(IMUBOSCH_BNO055) <<
"First read from the device failed, check everything is fine and retry";
624 int16_t raw_data[16];
631 if (!(this->*readFunc)(
REG_ACC_DATA, 32, response,
"Read all"))
633 yCError(IMUBOSCH_BNO055) <<
"Failed to read all the data";
641 for(
int i=0; i<16; i++)
643 raw_data[i] = response[responseOffset+1+i*2] << 8 | response[responseOffset+i*2];
647 quaternion_tmp = quaternion;
648 quaternion_tmp.w() = ((double)raw_data[12]) / (2 << 13);
649 quaternion_tmp.x() = ((double)raw_data[13]) / (2 << 13);
650 quaternion_tmp.y() = ((double)raw_data[14]) / (2 << 13);
651 quaternion_tmp.z() = ((double)raw_data[15]) / (2 << 13);
661 double sum_squared = quaternion_tmp.w() * quaternion_tmp.w() +
662 quaternion_tmp.x() * quaternion_tmp.x() +
663 quaternion_tmp.y() * quaternion_tmp.y() +
664 quaternion_tmp.z() * quaternion_tmp.z();
666 if( (sum_squared < 0.9) || (sum_squared > 1.2) )
674 data_tmp[0] = RPY_angle[0] * 180 /
M_PI;
675 data_tmp[1] = RPY_angle[1] * 180 /
M_PI;
676 data_tmp[2] = RPY_angle[2] * 180 /
M_PI;
679 data_tmp[3] = (double)raw_data[0] / 100.0;
680 data_tmp[4] = (double)raw_data[1] / 100.0;
681 data_tmp[5] = (double)raw_data[2] / 100.0;
685 data_tmp[6] = (double)raw_data[6] / 16.0;
686 data_tmp[7] = (double)raw_data[7] / 16.0;
687 data_tmp[8] = (double)raw_data[8] / 16.0;
690 data_tmp[9] = (double)raw_data[3] / 16.0;
691 data_tmp[10] = (double)raw_data[4] / 16.0;
692 data_tmp[11] = (double)raw_data[5] / 16.0;
697 std::lock_guard<std::mutex> guard(mutex);
699 quaternion = quaternion_tmp;
707 yCDebug(IMUBOSCH_BNO055,
"\t errors while reading data: %d", errs);
711 timeLastReport=m_timeStamp;
717 std::lock_guard<std::mutex> guard(mutex);
724 out[12] = quaternion.w();
725 out[13] = quaternion.x();
726 out[14] = quaternion.y();
727 out[15] = quaternion.z();
753 yCError(IMUBOSCH_BNO055) <<
"sens_index must be equal to 0, since there is only one sensor in consideration";
760 bool BoschIMU::genericGetSensorName(
size_t sens_index,
string& name)
const
764 yCError(IMUBOSCH_BNO055) <<
"sens_index must be equal to 0, since there is only one sensor in consideration";
772 bool BoschIMU::genericGetFrameName(
size_t sens_index,
string& frameName)
const
776 yCError(IMUBOSCH_BNO055) <<
"sens_index must be equal to 0, since there is only one sensor in consideration";
780 frameName = m_frameName;
793 return genericGetStatus(sens_index);
798 return genericGetSensorName(sens_index, name);
803 return genericGetFrameName(sens_index, frameName);
810 yCError(IMUBOSCH_BNO055) <<
"sens_index must be equal to 0, since there is only one sensor in consideration";
815 std::lock_guard<std::mutex> guard(mutex);
820 timestamp = m_timeStamp;
833 return genericGetStatus(sens_index);
838 return genericGetSensorName(sens_index, name);
843 return genericGetFrameName(sens_index, frameName);
850 yCError(IMUBOSCH_BNO055) <<
"sens_index must be equal to 0, since there is only one sensor in consideration";
855 std::lock_guard<std::mutex> guard(mutex);
860 timestamp = m_timeStamp;
871 return genericGetStatus(sens_index);
876 return genericGetSensorName(sens_index, name);
881 return genericGetFrameName(sens_index, frameName);
888 yCError(IMUBOSCH_BNO055) <<
"sens_index must be equal to 0, since there is only one sensor in consideration";
893 std::lock_guard<std::mutex> guard(mutex);
898 timestamp = m_timeStamp;
909 return genericGetStatus(sens_index);
914 return genericGetSensorName(sens_index, name);
919 return genericGetFrameName(sens_index, frameName);
926 yCError(IMUBOSCH_BNO055) <<
"sens_index must be equal to 0, since there is only one sensor in consideration";
931 std::lock_guard<std::mutex> guard(mutex);
933 out[0] = data[9] / 1000000;
934 out[1] = data[10]/ 1000000;
935 out[2] = data[11]/ 1000000;
937 timestamp = m_timeStamp;
944 yCTrace(IMUBOSCH_BNO055,
"Thread released");
void threadRelease() override
Terminate communication with the device and release the thread.
bool getThreeAxisGyroscopeMeasure(size_t sens_index, yarp::sig::Vector &out, double ×tamp) const override
Get three axis gyroscope measurements.
bool sendReadCommandSer(unsigned char register_add, int len, unsigned char *buf, std::string comment="")
bool checkReadResponse(unsigned char *response)
size_t getNrOfThreeAxisMagnetometers() const override
Get the number of three axis magnetometers in the device.
void printBuffer(unsigned char *buffer, int length)
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 getOrientationSensorFrameName(size_t sens_index, std::string &frameName) const override
Get the name of the frame in which orientation sensor measurements are expressed.
bool threadInit() override
Initialize process with desired device configurations.
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 ×tamp) const override
Get orientation sensor measurements.
bool checkWriteResponse(unsigned char *response)
bool calibrate(int ch, double v) override
Calibrate the sensor, single channel.
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.
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.
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.
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.
int readBytes(unsigned char *buffer, int bytes)
size_t getNrOfThreeAxisGyroscopes() const override
Get the number of three axis gyroscopes in the device.
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.
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 ×tamp) const override
Get three axis linear accelerometer measurements.
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 ×tamp) const override
Get three axis magnetometer measurements.
void run() override
Update loop where measurements are read from the device.
An abstraction for a periodic thread.
A base class for nested structures that can be searched.
virtual Value & find(const std::string &key) const =0
Gets a value corresponding to a given keyword.
virtual bool check(const std::string &key) const =0
Check if there exists a property of the given name.
virtual std::string toString() const =0
Return a standard text representation of the content of the object.
static double nowSystem()
static void delaySystem(double seconds)
A single value (typically within a Bottle).
virtual bool isString() const
Checks if value is a string.
std::string toString() const override
Return a standard text representation of the content of the object.
virtual std::string asString() const
Get string value.
void resize(size_t size) override
Resize the vector.
void zero()
Zero the elements of the vector.
#define ATTEMPTS_NUM_OF_SEND_CONFIG_CMD
#define REGISTER_NOT_READY
#define TIME_REPORT_INTERVAL
#define yCError(component,...)
#define yCTrace(component,...)
#define yCWarning(component,...)
#define yCDebug(component,...)
#define YARP_LOG_COMPONENT(name,...)
An interface for the device drivers.
MAS_status
Status of a given analog sensor exposed by a multiple analog sensors interface.
@ MAS_ERROR
The sensor is in generic error state.
@ MAS_OK
The sensor is working correctly.
yarp::sig::Vector dcm2rpy(const yarp::sig::Matrix &R)
Converts a dcm (direction cosine matrix) rotation matrix to roll-pitch-yaw angles (defined in Math....
void delay(double seconds)
Wait for a certain number of seconds.
An interface to the operating system, including Port based communication.
bool read(ImageOf< PixelRgb > &dest, const std::string &src, image_fileformat format=FORMAT_ANY)
bool write(const ImageOf< PixelRgb > &src, const std::string &dest, image_fileformat format=FORMAT_PPM)