diff --git a/src/axis_imu.cc b/src/axis_imu.cc
index 11b5285d18eea5f34935356a76f7fd3c1545251b..250d31018ef40f323456c69c295f756ef7bbcf3d 100644
--- a/src/axis_imu.cc
+++ b/src/axis_imu.cc
@@ -94,7 +94,7 @@ private:
   void handle_receive(const boost::system::error_code& error,
                       std::size_t bytes_transferred) {
     if (!error || error == boost::asio::error::message_size) {
-      // cerr << "Got message: " << bytes_transferred << " - " << recv_buffer_[0] << endl;
+      //      cerr << "Got message: " << bytes_transferred << " - " << recv_buffer_[0] << " - " << recv_buffer_[33] << endl;
       //      float time = bytesToFloat(recv_buffer_[1], recv_buffer_[2], recv_buffer_[3], recv_buffer_[4]);
       double gtime = bytesToDouble(1);
       //float ax, ay, az, gx, gy, gz;
@@ -103,15 +103,15 @@ private:
       gy = bytesToDouble(17);
       gz = bytesToDouble(25);
 
-      double atime = bytesToDouble(33);
-      ax = bytesToDouble(41);
-      ay = bytesToDouble(49);
-      az = bytesToDouble(57);
+      double atime = bytesToDouble(34);
+      ax = bytesToDouble(42);
+      ay = bytesToDouble(50);
+      az = bytesToDouble(58);
       if (recv_buffer_[0] == 'G') {
         have_gyro_flag = true;
         ROS_ERROR("         GYRO: %f - %f %f %f", gtime, gx, gy, gz);        
       }
-      if (recv_buffer_[32] == 'A') {
+      if (recv_buffer_[33] == 'A') {
         have_acc_flag = true;
         ROS_ERROR("ACCELEROMETER: %f - %f %f %f", atime, ax, ay, az);
       }
@@ -167,7 +167,7 @@ private:
       //      mag_msg.magnetic_field.y = data.b[1]*1e-6;
       //      mag_msg.magnetic_field.z = data.b[2]*1e-6;
 
-      ROS_ERROR("publish imu");
+      // ROS_ERROR("publish imu");
       // Publish the messages
       imu_pub.publish(imu_msg);
       //      mag_pub.publish(mag_msg);