|
| 1 | +#include "imu.h" |
| 2 | + |
| 3 | +#include <fcntl.h> |
| 4 | +#include <linux/i2c-dev.h> |
| 5 | +#include <linux/i2c.h> |
| 6 | +#include <sys/ioctl.h> |
| 7 | + |
| 8 | +#include <climits> // For SHRT_MAX |
| 9 | + |
| 10 | +#include "shared/constants.h" |
| 11 | +#include "software/logger/logger.h" |
| 12 | + |
| 13 | +// these functions taken from |
| 14 | +// https://git.kernel.org/pub/scm/utils/i2c-tools/i2c-tools.git/tree/lib/smbus.c |
| 15 | +static __s32 i2c_smbus_access(int file, char read_write, __u8 command, int size, |
| 16 | + union i2c_smbus_data* data) |
| 17 | +{ |
| 18 | + struct i2c_smbus_ioctl_data args; |
| 19 | + __s32 err; |
| 20 | + |
| 21 | + args.read_write = read_write; |
| 22 | + args.command = command; |
| 23 | + args.size = size; |
| 24 | + args.data = data; |
| 25 | + |
| 26 | + err = ioctl(file, I2C_SMBUS, &args); |
| 27 | + if (err == -1) |
| 28 | + err = -errno; |
| 29 | + return err; |
| 30 | +} |
| 31 | + |
| 32 | +static __s32 i2c_smbus_read_byte_data(int file, __u8 command) |
| 33 | +{ |
| 34 | + union i2c_smbus_data data; |
| 35 | + int err; |
| 36 | + |
| 37 | + err = i2c_smbus_access(file, I2C_SMBUS_READ, command, I2C_SMBUS_BYTE_DATA, &data); |
| 38 | + if (err < 0) |
| 39 | + return err; |
| 40 | + |
| 41 | + return 0x0FF & data.byte; |
| 42 | +} |
| 43 | + |
| 44 | +static __s32 i2c_smbus_write_byte_data(int file, __u8 command, __u8 value) |
| 45 | +{ |
| 46 | + union i2c_smbus_data data; |
| 47 | + data.byte = value; |
| 48 | + return i2c_smbus_access(file, I2C_SMBUS_WRITE, command, I2C_SMBUS_BYTE_DATA, &data); |
| 49 | +} |
| 50 | + |
| 51 | + |
| 52 | +ImuService::ImuService() : initialized_(false) |
| 53 | +{ |
| 54 | + // Establish connection to the IMU and verify that the who am I pin is correct. |
| 55 | + file_descriptor_ = open(IMU_DEVICE.c_str(), O_RDWR); |
| 56 | + int ret = ioctl(file_descriptor_, I2C_SLAVE_FORCE, 0x6b); |
| 57 | + if (ret < 0) |
| 58 | + { |
| 59 | + LOG(WARNING) |
| 60 | + << "Failed to initialize the IMU: failed to establish i2c connection."; |
| 61 | + return; |
| 62 | + } |
| 63 | + if (i2c_smbus_read_byte_data(file_descriptor_, WHOAMI_REG) != 106) |
| 64 | + { |
| 65 | + LOG(WARNING) << "Failed to initialize the IMU: WHOAMI register " |
| 66 | + << static_cast<int>(WHOAMI_REG) << " read incorrectly."; |
| 67 | + return; |
| 68 | + } |
| 69 | + // Attempt to enable gyro and accelerometer, checking that writes are successful |
| 70 | + // See lsm6dsl datasheet for how to set these registers. |
| 71 | + i2c_smbus_write_byte_data(file_descriptor_, ACCEL_CONTROL_REG, 0b01000000); |
| 72 | + if (i2c_smbus_read_byte_data(file_descriptor_, ACCEL_CONTROL_REG) != 0b01000000) |
| 73 | + { // write unsuccessful |
| 74 | + LOG(WARNING) |
| 75 | + << "Failed to initialize the IMU: writing to accelerometer config register " |
| 76 | + << static_cast<int>(ACCEL_CONTROL_REG) << " unsuccessful"; |
| 77 | + return; |
| 78 | + } |
| 79 | + // Set Gyroscope output data rate to 208 Hz, setting FS to 1000 dps (pg 61 of |
| 80 | + // datasheet for lsm6dsl, pg 21) |
| 81 | + i2c_smbus_write_byte_data(file_descriptor_, GYRO_CONTROL_REG, 0b01011000); |
| 82 | + if (i2c_smbus_read_byte_data(file_descriptor_, GYRO_CONTROL_REG) != 0b01011000) |
| 83 | + { // write unsuccessful |
| 84 | + LOG(WARNING) |
| 85 | + << "Failed to initialize the IMU: writing to gyroscope config register " |
| 86 | + << "unsuccessful"; |
| 87 | + return; |
| 88 | + } |
| 89 | + |
| 90 | + // Enable Gyro digital LPF1 and set bandwidth to ~65Hz (FTYPE=000) |
| 91 | + // CTRL4_C: bit 1 (LPF1_SEL_G) = 1 |
| 92 | + i2c_smbus_write_byte_data(file_descriptor_, CTRL4_C, 0b00000010); |
| 93 | + // CTRL6_C: bits 2:0 (FTYPE) = 000 |
| 94 | + i2c_smbus_write_byte_data(file_descriptor_, CTRL6_C, 0b00000000); |
| 95 | + |
| 96 | + // Enable Accelerometer digital LPF2 |
| 97 | + // CTRL8_XL: bit 7 (LPF2_XL_EN) = 1 |
| 98 | + i2c_smbus_write_byte_data(file_descriptor_, CTRL8_XL, 0b10000000); |
| 99 | + |
| 100 | + initialized_ = true; |
| 101 | + LOG(INFO) << "Initialized IMU! Calibrating..."; |
| 102 | + degrees_error_ = 0; |
| 103 | + // get 100 sample average of stationary reading, so all future readings can be |
| 104 | + // corrected |
| 105 | + double sum = 0; |
| 106 | + int valid_samples = 0; |
| 107 | + for (int i = 0; i < 100; i++) |
| 108 | + { |
| 109 | + // Fixed: Call the actual implemented function name |
| 110 | + auto poll = pollAngularVelocity(); |
| 111 | + if (poll.has_value()) |
| 112 | + { |
| 113 | + sum += poll->toDegrees(); |
| 114 | + valid_samples++; |
| 115 | + } |
| 116 | + usleep(50000); |
| 117 | + } |
| 118 | + |
| 119 | + // TODO (3421): More robust calibration |
| 120 | + if (valid_samples > 0) |
| 121 | + { |
| 122 | + degrees_error_ = sum / valid_samples; |
| 123 | + LOG(INFO) << "IMU Calibration complete. Offset: " << degrees_error_ << " dps"; |
| 124 | + } |
| 125 | + else |
| 126 | + { |
| 127 | + LOG(WARNING) << "IMU Calibration failed: no valid samples received. Angular " |
| 128 | + "stability will be poor."; |
| 129 | + initialized_ = false; |
| 130 | + } |
| 131 | + |
| 132 | + // Temporary: enable when need to calibrate |
| 133 | + // Eigen::Vector2d deviation = calibrate_imu(); |
| 134 | + // LOG(INFO) << "error: " << deviation.x() << deviation.y() << "."; |
| 135 | +} |
| 136 | + |
| 137 | +std::optional<ImuData> ImuService::poll() |
| 138 | +{ |
| 139 | + std::optional<AngularVelocity> angular_velocity = pollAngularVelocity(); |
| 140 | + std::optional<AngularAcceleration> angular_acceleration = |
| 141 | + pollAngularAcceleration(angular_velocity); |
| 142 | + std::optional<Eigen::Vector2d> imu_linear_acceleration = pollLinearAcceleration(); |
| 143 | + |
| 144 | + std::optional<Eigen::Vector2d> linear_acceleration; |
| 145 | + if (angular_velocity && angular_acceleration && imu_linear_acceleration) |
| 146 | + { |
| 147 | + linear_acceleration = transformLinearAcceleration( |
| 148 | + *angular_velocity, *angular_acceleration, *imu_linear_acceleration); |
| 149 | + } |
| 150 | + |
| 151 | + |
| 152 | + return ImuData{angular_velocity, angular_acceleration, linear_acceleration}; |
| 153 | +} |
| 154 | +std::optional<int16_t> ImuService::readAndCombineByteData(uint8_t ls_reg, uint8_t ms_reg) |
| 155 | +{ |
| 156 | + int least_significant = i2c_smbus_read_byte_data(file_descriptor_, ls_reg); |
| 157 | + int most_significant = i2c_smbus_read_byte_data(file_descriptor_, ms_reg); |
| 158 | + |
| 159 | + if (least_significant < 0 || most_significant < 0) |
| 160 | + { |
| 161 | + return std::nullopt; |
| 162 | + } |
| 163 | + |
| 164 | + uint16_t combined = (static_cast<uint8_t>(most_significant) << 8) | |
| 165 | + static_cast<uint8_t>(least_significant); |
| 166 | + |
| 167 | + return static_cast<int16_t>(combined); |
| 168 | +} |
| 169 | + |
| 170 | +std::optional<AngularVelocity> ImuService::pollAngularVelocity() |
| 171 | +{ |
| 172 | + if (!initialized_) |
| 173 | + { |
| 174 | + return std::nullopt; |
| 175 | + } |
| 176 | + |
| 177 | + std::optional<int16_t> opt_full_word = |
| 178 | + readAndCombineByteData(GYRO_LEAST_SIG_REG, GYRO_MOST_SIG_REG); |
| 179 | + |
| 180 | + if (!opt_full_word.has_value()) |
| 181 | + { |
| 182 | + return std::nullopt; |
| 183 | + } |
| 184 | + |
| 185 | + int16_t full_word = opt_full_word.value(); |
| 186 | + |
| 187 | + double degrees_per_sec = static_cast<double>(full_word) / |
| 188 | + static_cast<double>(SHRT_MAX) * IMU_FULL_SCALE_DPS; |
| 189 | + |
| 190 | + return AngularVelocity::fromRadians((degrees_per_sec - degrees_error_) * M_PI / 180); |
| 191 | +} |
| 192 | + |
| 193 | + |
| 194 | +std::optional<AngularAcceleration> ImuService::pollAngularAcceleration( |
| 195 | + std::optional<AngularVelocity> curr_angular_velocity) |
| 196 | +{ |
| 197 | + if (!initialized_) |
| 198 | + { |
| 199 | + return std::nullopt; |
| 200 | + } |
| 201 | + |
| 202 | + if (!prev_angular_velocity_.has_value()) |
| 203 | + { |
| 204 | + prev_angular_velocity_ = pollAngularVelocity(); |
| 205 | + prev_time_ = std::chrono::steady_clock::now(); |
| 206 | + return std::nullopt; |
| 207 | + } |
| 208 | + |
| 209 | + auto curr_time = std::chrono::steady_clock::now(); |
| 210 | + |
| 211 | + double dt = std::chrono::duration<double>(curr_time - prev_time_).count(); |
| 212 | + if (dt <= 0 || !curr_angular_velocity.has_value()) |
| 213 | + return std::nullopt; |
| 214 | + |
| 215 | + double alpha = |
| 216 | + (curr_angular_velocity->toRadians() - prev_angular_velocity_->toRadians()) / dt; |
| 217 | + |
| 218 | + prev_angular_velocity_ = curr_angular_velocity; |
| 219 | + prev_time_ = curr_time; |
| 220 | + |
| 221 | + return AngularAcceleration::fromRadians(alpha); |
| 222 | +} |
| 223 | + |
| 224 | + |
| 225 | + |
| 226 | +std::optional<Eigen::Vector2d> ImuService::pollLinearAcceleration() |
| 227 | +{ |
| 228 | + if (!initialized_) |
| 229 | + { |
| 230 | + return std::nullopt; |
| 231 | + } |
| 232 | + |
| 233 | + std::optional<int16_t> opt_x = |
| 234 | + readAndCombineByteData(ACCEL_X_LEAST_SIG_REG, ACCEL_X_MOST_SIG_REG); |
| 235 | + std::optional<int16_t> opt_y = |
| 236 | + readAndCombineByteData(ACCEL_Y_LEAST_SIG_REG, ACCEL_Y_MOST_SIG_REG); |
| 237 | + |
| 238 | + if (!opt_x.has_value() || !opt_y.has_value()) |
| 239 | + { |
| 240 | + return std::nullopt; |
| 241 | + } |
| 242 | + |
| 243 | + int16_t raw_x = opt_x.value(); |
| 244 | + int16_t raw_y = opt_y.value(); |
| 245 | + |
| 246 | + double a_x = (static_cast<double>(raw_x) / SHRT_MAX) * ACCELEROMETER_FULL_SCALE_G * |
| 247 | + ACCELERATION_DUE_TO_GRAVITY_METERS_PER_SECOND_SQUARED; |
| 248 | + |
| 249 | + double a_y = (static_cast<double>(raw_y) / SHRT_MAX) * ACCELEROMETER_FULL_SCALE_G * |
| 250 | + ACCELERATION_DUE_TO_GRAVITY_METERS_PER_SECOND_SQUARED; |
| 251 | + |
| 252 | + return Eigen::Vector2d(a_x, a_y); |
| 253 | +} |
| 254 | + |
| 255 | +Eigen::Vector2d ImuService::transformLinearAcceleration(AngularVelocity omega, |
| 256 | + AngularAcceleration alpha, |
| 257 | + Eigen::Vector2d imu_acceleration) |
| 258 | +{ |
| 259 | + Eigen::Vector2d r(IMU_OFFSET_X, IMU_OFFSET_Y); |
| 260 | + |
| 261 | + double w = omega.toRadians(); |
| 262 | + double a = alpha.toRadians(); |
| 263 | + |
| 264 | + // tangential: alpha x r → (-alpha*ry, alpha*rx) |
| 265 | + Eigen::Vector2d tangential(-a * r.y(), a * r.x()); |
| 266 | + |
| 267 | + // centripetal: omega^2 * r |
| 268 | + Eigen::Vector2d centripetal = (w * w) * r; |
| 269 | + |
| 270 | + return imu_acceleration + tangential - centripetal; |
| 271 | +} |
| 272 | + |
| 273 | +Eigen::Vector2d ImuService::calibrate_imu() |
| 274 | +{ |
| 275 | + LOG(INFO) << "Start IMU x,y calibration" << std::endl; |
| 276 | + Eigen::MatrixXd A(2 * 100, 2); |
| 277 | + Eigen::VectorXd b(2 * 100); |
| 278 | + int valid = 0; |
| 279 | + |
| 280 | + for (int i = 0; i < 100; i++) |
| 281 | + { |
| 282 | + // Fixed: Call the actual implemented function name |
| 283 | + auto omega_opt = pollAngularVelocity(); |
| 284 | + if (!omega_opt.has_value()) |
| 285 | + { |
| 286 | + continue; |
| 287 | + } |
| 288 | + auto alpha_opt = pollAngularAcceleration(omega_opt); |
| 289 | + auto acc = pollLinearAcceleration(); |
| 290 | + if (omega_opt.has_value() && alpha_opt.has_value() && acc.has_value()) |
| 291 | + { |
| 292 | + double omega = omega_opt->toRadians(); |
| 293 | + double alpha = alpha_opt->toRadians(); |
| 294 | + |
| 295 | + A(2 * valid, 0) = -omega * omega; |
| 296 | + A(2 * valid, 1) = -alpha; |
| 297 | + A(2 * valid + 1, 0) = alpha; |
| 298 | + A(2 * valid + 1, 1) = -omega * omega; |
| 299 | + |
| 300 | + b(2 * valid) = acc->x(); |
| 301 | + b(2 * valid + 1) = acc->y(); |
| 302 | + valid++; |
| 303 | + } |
| 304 | + usleep(100000); |
| 305 | + } |
| 306 | + if (valid < 10) |
| 307 | + { |
| 308 | + LOG(WARNING) << "Calibration failed: insufficient valid samples"; |
| 309 | + return Eigen::Vector2d(0.0, 0.0); |
| 310 | + } |
| 311 | + Eigen::MatrixXd A_valid = A.topRows(2 * valid); |
| 312 | + Eigen::VectorXd b_valid = b.topRows(2 * valid); |
| 313 | + Eigen::Vector2d X = |
| 314 | + A_valid.bdcSvd(Eigen::ComputeThinU | Eigen::ComputeThinV).solve(b_valid); |
| 315 | + return X; |
| 316 | +} |
0 commit comments