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

fix!: correct imu orientation #45

Merged
merged 1 commit into from
Aug 26, 2024
Merged
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 @@ -42,6 +42,17 @@ geometry_msgs::msg::Vector3 transformVector3(
return vec_stamped_transformed.vector;
}

geometry_msgs::msg::Quaternion transformQuaternion(
const geometry_msgs::msg::Quaternion & quat, const geometry_msgs::msg::TransformStamped & transform)
{
geometry_msgs::msg::QuaternionStamped quat_stamped;
quat_stamped.quaternion = quat;

geometry_msgs::msg::QuaternionStamped quat_stamped_transformed;
tf2::doTransform(quat_stamped, quat_stamped_transformed, transform);
return quat_stamped_transformed.quaternion;
}

namespace imu_corrector
{
ImuCorrector::ImuCorrector(const rclcpp::NodeOptions & node_options)
Expand Down Expand Up @@ -103,6 +114,7 @@ void ImuCorrector::callbackImu(const sensor_msgs::msg::Imu::ConstSharedPtr imu_m
sensor_msgs::msg::Imu imu_msg_base_link;
imu_msg_base_link.header.stamp = imu_msg_ptr->header.stamp;
imu_msg_base_link.header.frame_id = output_frame_;
imu_msg_base_link.orientation = transformQuaternion(imu_msg.orientation, *tf_imu2base_ptr);
imu_msg_base_link.linear_acceleration =
transformVector3(imu_msg.linear_acceleration, *tf_imu2base_ptr);
imu_msg_base_link.linear_acceleration_covariance =
Expand Down