Skip to content

Commit

Permalink
primary imu data
Browse files Browse the repository at this point in the history
  • Loading branch information
Astik-2002 committed Feb 20, 2024
1 parent c65fe18 commit f1fce9d
Showing 1 changed file with 4 additions and 3 deletions.
7 changes: 4 additions & 3 deletions libraries/AP_DDS/AP_DDS_Client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -435,9 +435,10 @@ void AP_DDS_Client::update_topic(sensor_msgs_msg_Imu& msg)
msg.orientation.w = orientation[3];
}
msg.orientation_covariance[0] = -1;

Vector3f accel_data = imu.get_accel();
Vector3f gyro_data = imu.get_gyro();
uint8_t accel_index = ahrs.get_primary_accel_index();
uint8_t gyro_index = ahrs.get_primary_gyro_index();
const Vector3f accel_data = imu.get_accel(accel_index);
const Vector3f gyro_data = imu.get_gyro(gyro_index);

// Populate the message fields
msg.linear_acceleration.x = accel_data.x;
Expand Down

0 comments on commit f1fce9d

Please sign in to comment.