Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Mx/rotate to enu #187

Draft
wants to merge 9 commits into
base: humble
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -13,9 +13,9 @@ def generate_launch_description():
parameters=[
{'do_bias_estimation': True},
{'do_adaptive_gain': True},
{'use_mag': False},
{'gain_acc': 0.01},
{'gain_mag': 0.01},
{'use_mag': True},
{'gain_acc': 0.1},
{'gain_mag': 0.1},
],
)
]
Expand Down
19 changes: 13 additions & 6 deletions imu_complementary_filter/src/complementary_filter_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -69,12 +69,13 @@ ComplementaryFilterROS::ComplementaryFilterROS()
}

// Register IMU raw data subscriber.
imu_subscriber_.reset(new ImuSubscriber(this, "/imu/data_raw"));
rmw_qos_profile_t qos = rmw_qos_profile_sensor_data;
imu_subscriber_.reset(new ImuSubscriber(this, "/imu/data_raw", qos));

// Register magnetic data subscriber.
if (use_mag_)
{
mag_subscriber_.reset(new MagSubscriber(this, "/imu/mag"));
mag_subscriber_.reset(new MagSubscriber(this, "/imu/mag", qos));

sync_.reset(new Synchronizer(SyncPolicy(queue_size), *imu_subscriber_,
*mag_subscriber_));
Expand Down Expand Up @@ -241,12 +242,18 @@ void ComplementaryFilterROS::publish(ImuMsg::ConstSharedPtr imu_msg_raw)
filter_.getOrientation(q0, q1, q2, q3);
tf2::Quaternion q = hamiltonToTFQuaternion(q0, q1, q2, q3);

//Rotate orientation to report in ENU coordinate convention instead of NWU. -- Alpistinho
tf2::Quaternion qRot;
qRot.setRPY( 0, 0, M_PI/2.0 );
q = qRot*q;
q.normalize();

// Create and publish fitlered IMU message.
ImuMsg::SharedPtr imu_msg = std::make_shared<ImuMsg>(*imu_msg_raw);
imu_msg->orientation.x = q1;
imu_msg->orientation.y = q2;
imu_msg->orientation.z = q3;
imu_msg->orientation.w = q0;
imu_msg->orientation.x = q.x();
imu_msg->orientation.y = q.y();
imu_msg->orientation.z = q.z();
imu_msg->orientation.w = q.w();

imu_msg->orientation_covariance[0] = orientation_variance_;
imu_msg->orientation_covariance[1] = 0.0;
Expand Down
Loading