Skip to content

Commit

Permalink
Imu improvements - Humble (#305)
Browse files Browse the repository at this point in the history
  • Loading branch information
Serafadam authored May 12, 2023
1 parent 29c2906 commit 11f8784
Show file tree
Hide file tree
Showing 31 changed files with 420 additions and 362 deletions.
23 changes: 23 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -148,6 +148,29 @@ Additionally you can set `i.output_isp: false` to use `video` output and set cus
![](docs/param_rgb.gif)
#### Setting Stereo parameters
![](docs/param_stereo.gif)

#### Setting IMU parameters
Parameters:
* `i_acc_freq: 400` - Accelerometer sensor frequency
* `i_acc_cov: 0.0` - Accelerometer covariance
* `i_batch_report_threshold: 1` - Batch report size
* `i_enable_rotation: false` - Whether to enable rotation vector & magnetometer data (available when using IMU_WITH_MAGN/ IMU_WITH_MAGN_SPLIT message type)
* `i_gyro_cov: 0.0` - Gyroscope covariance
* `i_gyro_freq: 400` - Gyroscope frequency
* `i_mag_cov: 0.0` - Magnetometer covariance
* `i_mag_freq: 100` - Magnetometer frequency
* `i_max_batch_reports: 10` - Max reports per batch
* `i_message_type: IMU` - ROS publisher type:
* `IMU` - sensor_msgs/Imu
* `IMU_WITH_MAG` - depthai_ros_msgs/ImuWithMagneticField
* `IMU_WITH_MAG_SPLIT` - two publishers - sensor_msgs/Imu & sensor_msgs/MagneticField
* `i_rot_cov: -1.0` - Rotation covariance
* `i_rot_freq: 400` - Rotation frequency
* `i_sync_method: LINEAR_INTERPOLATE_ACCEL` - sync method. Available options:
* `COPY`
* `LINEAR_INTERPOLATE_GYRO`
* `LINEAR_INTERPOLATE_ACCEL`

#### Stopping/starting camera for power saving/reconfiguration
![](docs/start_stop.gif)

Expand Down
3 changes: 3 additions & 0 deletions depthai-ros/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package depthai-ros
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.7.2 (20230-5-08)
* IMU improvements

2.7.1 (2023-03-29)
-------------------
* Add custom output size option for streams
Expand Down
2 changes: 1 addition & 1 deletion depthai-ros/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
cmake_minimum_required(VERSION 3.10.2) # CMake version in Ubuntu 18.04 LTS

project(depthai-ros VERSION 2.7.1 LANGUAGES CXX C)
project(depthai-ros VERSION 2.7.2 LANGUAGES CXX C)

set(CMAKE_CXX_STANDARD 14)

Expand Down
2 changes: 1 addition & 1 deletion depthai-ros/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="3">
<name>depthai-ros</name>
<version>2.7.1</version>
<version>2.7.2</version>
<description>The depthai-ros package</description>

<!-- One maintainer tag required, multiple allowed, one person per tag -->
Expand Down
2 changes: 1 addition & 1 deletion depthai_bridge/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
cmake_minimum_required(VERSION 3.10.2) # CMake version in Ubuntu 18.04 LTS
set(CMAKE_POSITION_INDEPENDENT_CODE ON)

project(depthai_bridge VERSION 2.7.1 LANGUAGES CXX C)
project(depthai_bridge VERSION 2.7.2 LANGUAGES CXX C)

set(CMAKE_CXX_STANDARD 14)
set(CMAKE_CXX_STANDARD_REQUIRED ON)
Expand Down
158 changes: 153 additions & 5 deletions depthai_bridge/include/depthai_bridge/ImuConverter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,8 +9,11 @@

#include "depthai-shared/datatype/RawIMUData.hpp"
#include "depthai/pipeline/datatype/IMUData.hpp"
#include "depthai_bridge/depthaiUtility.hpp"
#include "depthai_ros_msgs/msg/imu_with_magnetic_field.hpp"
#include "rclcpp/time.hpp"
#include "sensor_msgs/msg/imu.hpp"
#include "sensor_msgs/msg/magnetic_field.hpp"

namespace dai {

Expand All @@ -26,20 +29,165 @@ class ImuConverter {
ImuConverter(const std::string& frameName,
ImuSyncMethod syncMode = ImuSyncMethod::LINEAR_INTERPOLATE_ACCEL,
double linear_accel_cov = 0.0,
double angular_velocity_cov = 0.0);
double angular_velocity_cov = 0.0,
double rotation_cov = 0.0,
double magnetic_field_cov = 0.0,
bool enable_rotation = false);
~ImuConverter();
void toRosMsg(std::shared_ptr<dai::IMUData> inData, std::deque<ImuMsgs::Imu>& outImuMsg);
void toRosMsg(std::shared_ptr<dai::IMUData> inData, std::deque<ImuMsgs::Imu>& outImuMsgs);
void toRosDaiMsg(std::shared_ptr<dai::IMUData> inData, std::deque<depthai_ros_msgs::msg::ImuWithMagneticField>& outImuMsgs);

template <typename T>
T lerp(const T& a, const T& b, const double t) {
return a * (1.0 - t) + b * t;
}

template <typename T>
T lerpImu(const T& a, const T& b, const double t) {
T res;
res.x = lerp(a.x, b.x, t);
res.y = lerp(a.y, b.y, t);
res.z = lerp(a.z, b.z, t);
return res;
}

private:
void FillImuData_LinearInterpolation(std::vector<IMUPacket>& imuPackets, std::deque<ImuMsgs::Imu>& imuMsgs);
ImuMsgs::Imu CreateUnitMessage(dai::IMUReportAccelerometer accel, dai::IMUReportGyroscope gyro);
template <typename T>
void FillImuData_LinearInterpolation(std::vector<IMUPacket>& imuPackets, std::deque<T>& imuMsgs) {
static std::deque<dai::IMUReportAccelerometer> accelHist;
static std::deque<dai::IMUReportGyroscope> gyroHist;
static std::deque<dai::IMUReportRotationVectorWAcc> rotationHist;
static std::deque<dai::IMUReportMagneticField> magnHist;

for(int i = 0; i < imuPackets.size(); ++i) {
if(accelHist.size() == 0) {
accelHist.push_back(imuPackets[i].acceleroMeter);
} else if(accelHist.back().sequence != imuPackets[i].acceleroMeter.sequence) {
accelHist.push_back(imuPackets[i].acceleroMeter);
}

if(gyroHist.size() == 0) {
gyroHist.push_back(imuPackets[i].gyroscope);
} else if(gyroHist.back().sequence != imuPackets[i].gyroscope.sequence) {
gyroHist.push_back(imuPackets[i].gyroscope);
}

if(_enable_rotation && rotationHist.size() == 0) {
rotationHist.push_back(imuPackets[i].rotationVector);
} else if(_enable_rotation && rotationHist.back().sequence != imuPackets[i].rotationVector.sequence) {
rotationHist.push_back(imuPackets[i].rotationVector);
} else {
rotationHist.resize(accelHist.size());
}

if(_enable_rotation && magnHist.size() == 0) {
magnHist.push_back(imuPackets[i].magneticField);
} else if(_enable_rotation && magnHist.back().sequence != imuPackets[i].magneticField.sequence) {
magnHist.push_back(imuPackets[i].magneticField);
} else {
magnHist.resize(accelHist.size());
}

if(_syncMode == ImuSyncMethod::LINEAR_INTERPOLATE_ACCEL) {
if(accelHist.size() < 3) {
continue;
} else {
interpolate(accelHist, gyroHist, rotationHist, magnHist, imuMsgs);
}

} else if(_syncMode == ImuSyncMethod::LINEAR_INTERPOLATE_GYRO) {
if(gyroHist.size() < 3) {
continue;
} else {
interpolate(gyroHist, accelHist, rotationHist, magnHist, imuMsgs);
}
}
}
}

uint32_t _sequenceNum;
double _linear_accel_cov, _angular_velocity_cov;
double _linear_accel_cov, _angular_velocity_cov, _rotation_cov, _magnetic_field_cov;
bool _enable_rotation;
const std::string _frameName = "";
ImuSyncMethod _syncMode;
std::chrono::time_point<std::chrono::steady_clock> _steadyBaseTime;
rclcpp::Time _rosBaseTime;

void fillImuMsg(dai::IMUReportAccelerometer report, ImuMsgs::Imu& msg);
void fillImuMsg(dai::IMUReportGyroscope report, ImuMsgs::Imu& msg);
void fillImuMsg(dai::IMUReportRotationVectorWAcc report, ImuMsgs::Imu& msg);
void fillImuMsg(dai::IMUReportMagneticField report, ImuMsgs::Imu& msg);

void fillImuMsg(dai::IMUReportAccelerometer report, depthai_ros_msgs::msg::ImuWithMagneticField& msg);
void fillImuMsg(dai::IMUReportGyroscope report, depthai_ros_msgs::msg::ImuWithMagneticField& msg);
void fillImuMsg(dai::IMUReportRotationVectorWAcc report, depthai_ros_msgs::msg::ImuWithMagneticField& msg);
void fillImuMsg(dai::IMUReportMagneticField report, depthai_ros_msgs::msg::ImuWithMagneticField& msg);

template <typename I, typename S, typename T, typename F, typename M>
void CreateUnitMessage(I first, S second, T third, F fourth, M& msg, dai::Timestamp timestamp) {
fillImuMsg(first, msg);
fillImuMsg(second, msg);
fillImuMsg(third, msg);
fillImuMsg(fourth, msg);

msg.header.frame_id = _frameName;

msg.header.stamp = getFrameTime(_rosBaseTime, _steadyBaseTime, timestamp.get());
}

template <typename I, typename S, typename T, typename F, typename M>
void interpolate(std::deque<I>& interpolated, std::deque<S>& second, std::deque<T>& third, std::deque<F>& fourth, std::deque<M>& imuMsgs) {
I interp0, interp1;
S currSecond;
T currThird;
F currFourth;
interp0.sequence = -1;
while(interpolated.size()) {
if(interp0.sequence == -1) {
interp0 = interpolated.front();
interpolated.pop_front();
} else {
interp1 = interpolated.front();
interpolated.pop_front();
// remove std::milli to get in seconds
std::chrono::duration<double, std::milli> duration_ms = interp1.timestamp.get() - interp0.timestamp.get();
double dt = duration_ms.count();
while(second.size()) {
currSecond = second.front();
currThird = third.front();
currFourth = fourth.front();
if(currSecond.timestamp.get() > interp0.timestamp.get() && currSecond.timestamp.get() <= interp1.timestamp.get()) {
// remove std::milli to get in seconds
std::chrono::duration<double, std::milli> diff = currSecond.timestamp.get() - interp0.timestamp.get();
const double alpha = diff.count() / dt;
I interp = lerpImu(interp0, interp1, alpha);
M msg;
CreateUnitMessage(interp, currSecond, currThird, currFourth, msg, currSecond.timestamp);
imuMsgs.push_back(msg);
second.pop_front();
third.pop_front();
fourth.pop_front();
} else if(currSecond.timestamp.get() > interp1.timestamp.get()) {
interp0 = interp1;
if(interpolated.size()) {
interp1 = interpolated.front();
interpolated.pop_front();
duration_ms = interp1.timestamp.get() - interp0.timestamp.get();
dt = duration_ms.count();
} else {
break;
}
} else {
second.pop_front();
third.pop_front();
fourth.pop_front();
}
}
interp0 = interp1;
}
}
interpolated.push_back(interp0);
}
};

} // namespace ros
Expand Down
14 changes: 0 additions & 14 deletions depthai_bridge/include/depthai_bridge/depthaiUtility.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,19 +84,5 @@ inline rclcpp::Time getFrameTime(rclcpp::Time rclBaseTime,
return rclStamp;
}

template <typename T>
T lerp(const T& a, const T& b, const double t) {
return a * (1.0 - t) + b * t;
}

template <typename T>
T lerpImu(const T& a, const T& b, const double t) {
T res;
res.x = lerp(a.x, b.x, t);
res.y = lerp(a.y, b.y, t);
res.z = lerp(a.z, b.z, t);
return res;
}

} // namespace ros
} // namespace dai
2 changes: 1 addition & 1 deletion depthai_bridge/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="3">
<name>depthai_bridge</name>
<version>2.7.1</version>
<version>2.7.2</version>
<description>The depthai_bridge package</description>

<maintainer email="[email protected]">Sachin Guruswamy</maintainer>
Expand Down
Loading

0 comments on commit 11f8784

Please sign in to comment.