diff --git a/CHANGELOG.md b/CHANGELOG.md index 643d4af..9d1879b 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -250,4 +250,15 @@ author: [byq77](https://github.com/byq77) ### Fixed - fixed the bug in the odometry - - reverted odometry params \ No newline at end of file + - reverted odometry params + +## [0.14.5] + +TODO: add changes + +## [0.15.0] - 2021-10-20 + +### Fixed +- Fixed acc bug for both imu sensors. +- Fixed the imu acc and gyro units to match units in the sensor_msgs/Imu message. +- Fixed acc vector orientation for mpu9250. \ No newline at end of file diff --git a/README.md b/README.md index d9c16cb..cc04376 100644 --- a/README.md +++ b/README.md @@ -9,7 +9,7 @@ ______ _____ _____ _ _ __ | |\ \ \ \_/ //\__/ /| |_) || (_) || |_ | | \ V V / \_| \_| \___/ \____/ |_.__/ \___/ \__| |_| \_/\_/ ``` -**Firmware version:** `0.14.5` +**Firmware version:** `0.15.0` ## Prerequisites You need to install following tools: diff --git a/lib/imu-driver b/lib/imu-driver index a9ca64b..dcfffa9 160000 --- a/lib/imu-driver +++ b/lib/imu-driver @@ -1 +1 @@ -Subproject commit a9ca64b8755cd5eb2db0a767a4b4aecfdac2bb49 +Subproject commit dcfffa9bf670aef9b285bddfc49482ea45b40108 diff --git a/mbed_app.json b/mbed_app.json index 47e601f..1df6d35 100644 --- a/mbed_app.json +++ b/mbed_app.json @@ -1,6 +1,6 @@ { "macros": [ - "ROSBOT_FW_VERSION=\"0.14.5\"", + "ROSBOT_FW_VERSION=\"0.15.0\"", "WELLCOME_BANNER" ], "target_overrides": { diff --git a/src/main.cpp b/src/main.cpp index 1adf8c6..38388d8 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -1149,18 +1149,21 @@ int main() if(nh.connected()) { - int i = 0; imu_msg.header.stamp = nh.now(message->timestamp); - imu_msg.orientation.x = message->orientation[i]; - imu_msg.angular_velocity.x = message->angular_velocity[i]; - imu_msg.linear_acceleration.x = message->angular_velocity[i++]; - imu_msg.orientation.y = message->orientation[i]; - imu_msg.angular_velocity.y = message->angular_velocity[i]; - imu_msg.linear_acceleration.y = message->angular_velocity[i++]; - imu_msg.orientation.z = message->orientation[i]; - imu_msg.angular_velocity.z = message->angular_velocity[i]; - imu_msg.linear_acceleration.z = message->angular_velocity[i++]; - imu_msg.orientation.w = message->orientation[i]; + + imu_msg.orientation.x = message->orientation[0]; + imu_msg.orientation.y = message->orientation[1]; + imu_msg.orientation.z = message->orientation[2]; + imu_msg.orientation.w = message->orientation[3]; + + imu_msg.angular_velocity.x = message->angular_velocity[0]; + imu_msg.angular_velocity.y = message->angular_velocity[1]; + imu_msg.angular_velocity.z = message->angular_velocity[2]; + + imu_msg.linear_acceleration.x = message->linear_acceleration[0]; + imu_msg.linear_acceleration.y = message->linear_acceleration[1]; + imu_msg.linear_acceleration.z = message->linear_acceleration[2]; + imu_pub->publish(&imu_msg); }