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

Use TF2 package for quaternion conversion #1031

Merged
Merged
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
2 changes: 2 additions & 0 deletions image_proc/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,8 @@
<depend>rclcpp_components</depend>
<depend>rcutils</depend>
<depend>sensor_msgs</depend>
<depend>tf2</depend>
<depend>tf2_geometry_msgs</depend>
<depend>tracetools_image_pipeline</depend>

<test_depend>ament_lint_auto</test_depend>
Expand Down
12 changes: 6 additions & 6 deletions image_proc/src/track_marker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,8 @@
// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.

#include <tf2/LinearMath/Quaternion.h>

#include <cstddef>
#include <functional>
#include <memory>
Expand All @@ -40,9 +42,9 @@
#include <image_proc/track_marker.hpp>
#include <image_proc/utils.hpp>
#include <image_transport/image_transport.hpp>
#include <opencv2/core/quaternion.hpp>
#include <rclcpp/qos.hpp>
#include <rclcpp/rclcpp.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>

namespace image_proc
{
Expand Down Expand Up @@ -135,11 +137,9 @@ void TrackMarkerNode::imageCb(
pose.pose.position.y = tvecs[0][1];
pose.pose.position.z = tvecs[0][2];
// Convert angle-axis to quaternion
cv::Quatd q = cv::Quatd::createFromRvec(rvecs[0]);
pose.pose.orientation.x = q.x;
pose.pose.orientation.y = q.y;
pose.pose.orientation.z = q.z;
pose.pose.orientation.w = q.w;
const tf2::Vector3 rvec(rvecs[0][0], rvecs[0][1], rvecs[0][2]);
const tf2::Quaternion q(rvec.normalized(), rvec.length());
tf2::convert(q, pose.pose.orientation);
pub_->publish(pose);
}
}
Expand Down