Skip to content

Commit

Permalink
Convert acceleration from G to m/s^2 to be conform with REP-103.
Browse files Browse the repository at this point in the history
  • Loading branch information
romainreignier committed Aug 4, 2017
1 parent 5f7b8a7 commit a1b7b40
Showing 1 changed file with 9 additions and 3 deletions.
12 changes: 9 additions & 3 deletions src/rtimulib_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,8 @@
#include <ros/ros.h>
#include <sensor_msgs/Imu.h>

static const double G_TO_MPSS = 9.80665;

int main(int argc, char **argv)
{
ros::init(argc, argv, "rtimulib_node");
Expand Down Expand Up @@ -85,18 +87,22 @@ int main(int argc, char **argv)
if (imu->IMURead())
{
RTIMU_DATA imu_data = imu->getIMUData();

imu_msg.header.stamp = ros::Time::now();
imu_msg.header.frame_id = frame_id;

imu_msg.orientation.x = imu_data.fusionQPose.x();
imu_msg.orientation.y = imu_data.fusionQPose.y();
imu_msg.orientation.z = imu_data.fusionQPose.z();
imu_msg.orientation.w = imu_data.fusionQPose.scalar();

imu_msg.angular_velocity.x = imu_data.gyro.x();
imu_msg.angular_velocity.y = imu_data.gyro.y();
imu_msg.angular_velocity.z = imu_data.gyro.z();
imu_msg.linear_acceleration.x = imu_data.accel.x();
imu_msg.linear_acceleration.y = imu_data.accel.y();
imu_msg.linear_acceleration.z = imu_data.accel.z();

imu_msg.linear_acceleration.x = imu_data.accel.x() * G_TO_MPSS;
imu_msg.linear_acceleration.y = imu_data.accel.y() * G_TO_MPSS;
imu_msg.linear_acceleration.z = imu_data.accel.z() * G_TO_MPSS;

imu_pub.publish(imu_msg);
}
Expand Down

0 comments on commit a1b7b40

Please sign in to comment.