Skip to content

Commit

Permalink
0.15.0 release
Browse files Browse the repository at this point in the history
  • Loading branch information
byq77 committed Oct 20, 2021
1 parent e4174cb commit d2c8191
Show file tree
Hide file tree
Showing 5 changed files with 29 additions and 15 deletions.
13 changes: 12 additions & 1 deletion CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -250,4 +250,15 @@ author: [byq77](https://github.com/byq77)

### Fixed
- fixed the bug in the odometry
- reverted odometry params
- 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.
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ ______ _____ _____ _ _ __
| |\ \ \ \_/ //\__/ /| |_) || (_) || |_ | | \ V V /
\_| \_| \___/ \____/ |_.__/ \___/ \__| |_| \_/\_/
```
**Firmware version:** `0.14.5`
**Firmware version:** `0.15.0`

## Prerequisites
You need to install following tools:
Expand Down
2 changes: 1 addition & 1 deletion lib/imu-driver
Submodule imu-driver updated 1 files
+44 −20 ImuDriver.cpp
2 changes: 1 addition & 1 deletion mbed_app.json
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
{
"macros": [
"ROSBOT_FW_VERSION=\"0.14.5\"",
"ROSBOT_FW_VERSION=\"0.15.0\"",
"WELLCOME_BANNER"
],
"target_overrides": {
Expand Down
25 changes: 14 additions & 11 deletions src/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}

Expand Down

0 comments on commit d2c8191

Please sign in to comment.