Skip to content

Commit

Permalink
Fix transformations to use correct parents and children frames
Browse files Browse the repository at this point in the history
  • Loading branch information
Samuel Toledano committed Oct 29, 2024
1 parent 4e7034b commit ccc193a
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 3 deletions.
4 changes: 2 additions & 2 deletions src/message_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1036,7 +1036,7 @@ const nav_msgs::msg::Odometry MessageWrapper::createRosOdoMessage(const sbg_driv
pose.position.y = first_valid_northing_;
pose.position.z = first_valid_altitude_;

fillTransform(odom_init_frame_id_, odom_frame_id_, pose, transform);
fillTransform(odom_init_frame_id_, odom_base_frame_id_, pose, transform);
tf_broadcaster_->sendTransform(transform);
static_tf_broadcaster_->sendTransform(transform);
}
Expand Down Expand Up @@ -1084,7 +1084,7 @@ const nav_msgs::msg::Odometry MessageWrapper::createRosOdoMessage(const sbg_driv
if (odom_publish_tf_)
{
// Publish odom transformation.
fillTransform(odo_ros_msg.header.frame_id, odom_base_frame_id_, odo_ros_msg.pose.pose, transform);
fillTransform(odom_base_frame_id_, odo_ros_msg.header.frame_id, odo_ros_msg.pose.pose, transform);
tf_broadcaster_->sendTransform(transform);
}

Expand Down
2 changes: 1 addition & 1 deletion urdf/ellipse.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
<visual>
<origin xyz="0 0 0" rpy="1.5708 0 -1.5708"/> <!-- Add rotation to align the 3D model with odometry -->
<geometry>
<mesh filename="package://sbg_driver/meshes/ellipse.stl" scale="0.1 0.1 0.1"/>
<mesh filename="package://sbg_driver/meshes/ellipse.stl" scale="0.01 0.01 0.01"/>
</geometry>
</visual>
</link>
Expand Down

0 comments on commit ccc193a

Please sign in to comment.