Aerial Robotics IITK
  • Introduction
  • Danger Zone
  • Tutorials
    • Workspace Setup
      • Installing Ubuntu
      • Basic Linux Setup
      • Spruce up your space
      • ROS Setup
      • PX4 Setup
        • PX4 Toolchain Setup
      • Ardupilot Setup
      • Installing Ground Control Station
        • QGroundControl
        • Mission Planner
      • ArduPilot Setup on Docker
      • PX4 Setup on Docker
    • How to Write a ROS Package
      • ROS Package
      • Node Handles, Parameters, and Topics
      • Coding Standards
      • Custom mavros message
      • Transformations
      • Conversions
    • Cheatsheets
      • CMakeCheatsheet
      • GitCheatsheet
      • LatexCheatsheet
      • Markdown Cheatsheet
    • Miscellaneous
      • Odroid XU4 Setup
      • Simulation using Offboard Control
        • Enable Offboard Mode in PX4
      • Writing a UDev rule
      • Sensor fusion
    • Reference wiki links
  • Concepts
    • Quaternions
      • Theory
    • Kalman Filters
    • Rotations
    • Path Planning
      • Grassfire Algorithm
      • Dijkstra Algorithm
      • A* Algorithm
      • Probabilistic Roadmap
      • RRT Algorithm
      • Visibility Graph Analysis
    • Lectures
      • Aerial Robotics
      • Avionics
      • Control Systems: Introduction
      • Control Systems: Models
      • Inter IIT Tech Meet 2018
      • Kalman Filters
      • Linux and Git
      • Git Tutorial
      • ROS
      • Rotorcraft
      • Software Training
  • Control System
    • Model Predictive Control
      • System Identification
      • Sample SysId Launch Files
      • Running MPC
        • MPC with Rotors
        • MPC with PX4 Sim
        • MPC with ROS
      • References
    • PID Controller
      • Introduction
      • Basic Theory
  • Estimation
    • Visual-Inertial Odometry
      • Hardware Requirements
      • Visual-Inertial Sensing
      • DIYing a VI-Sensor
    • Setup with VICON
    • Odometry from pose data
  • Computer Vision
    • Intel RealSense D435i setup for ROS Noetic
    • IntelRealSense D435i Calibration
    • Camera Calibration
    • ArUco ROS
  • Machine Learning
    • Datasets
  • Hardware Integration
    • Configuring Radio Telemetry
    • Setting up RTK + GPS
    • Integration of Sensors with PixHawk
      • Connecting Lidar-lite through I2C
    • Connections
    • Setting up Offboard Mission
      • Setting up Companion Computer
        • Raspberry Pi 4B Setup
        • Jetson TX2 Setup
      • Communication Setup
      • Guided mode
    • Miscellaneous
  • Resources
    • Open-source algorithms and resources
    • Courses
      • State Space Modelling of a Multirotor
      • Path Planning Lecture
      • Introduction to AI in Robotics
      • RRT, RRT* and RRT*- Path Planning Algorithms
    • Useful Reading Links
      • Aerial Robotics
      • Books
      • Computer Vision and Image Processing
      • Courses on AI and Robotics
      • Deep Neural Network
      • Dynamics and Controls system
      • Motion Planning
      • Probabilistic Robotics
      • Programming
      • Robotics Hardware
      • Miscellaneous and Awesome
    • Online Purchase websites
  • Competitions
    • Inter-IIT TechMeet 8.0
    • Inter-IIT TechMeet 9.0
    • IMAV 2019, Madrid, Spain
    • Inter-IIT TechMeet 10.0
    • Inter-IIT TechMeet 11.0
Powered by GitBook
On this page
  • Eigen
  • TF
  • minkindr (aslam::Transformation)
  • OpenCV Image

Was this helpful?

  1. Tutorials
  2. How to Write a ROS Package

Conversions

Converting data across libraries.

PreviousTransformationsNextCheatsheets

Last updated 1 year ago

Was this helpful?

The data source/sink is:

Eigen

To go to/from messages, use (or below).

Example:

#include <eigen_conversions/eigen_msg.h>

Eigen::Vector3d my_super_cool_vector(1.0, 2.0, 3.0);
geometry_msgs::Point point_msg;
tf::pointEigenToMsg(my_super_cool_vector, point_msg);
super_cool_publisher_.publish(point_msg);

TF

To go to/from TF, use (or also below).

Example:

#include <tf_conversions/tf_eigen.h>

Eigen::Vector3d my_super_cool_vector(1.0, 2.0, 3.0);
tf::Vector3 my_super_cool_vector_tf;
tf::vectorEigenToTF(my_super_cool_vector, my_super_cool_vector_tf);
tf::Transform transform;
transform.setOrigin(my_super_cool_vector_tf);
transform_broadcaster_.sendTransform(
    tf::StampedTransform(transform, ros::Time::now(), "map", "world"));

minkindr (aslam::Transformation)

Example:

#include <minkindr_conversions/kindr_msg.h>
#include <minkindr_conversions/kindr_tf.h>

Eigen::Quaterniond rotation(Eigen::Vector4d::Random());
rotation.normalize();
Eigen::Vector3d position(Eigen::Vector3d::Random());
kindr::minimal::QuatTransformation kindr_transform(rotation, position);

geometry_msgs::Pose msg;
tf::poseKindrToMsg(kindr_transform, &msg);
publisher_.publish(msg);

tf::Transform tf_transform;
tf::transformKindrToTF(kindr_transform, &tf_transform);
transform_broadcaster_.sendTransform(
    tf::StampedTransform(tf_transform, ros::Time::now(), "map", "world"));

OpenCV Image

Example:

#include <cv_bridge/cv_bridge.h>

const stereo_msgs::DisparityImageConstPtr& msg;  // We got this from a subscription callback.
cv::Mat output_image;
cv_bridge::CvImageConstPtr cv_img_ptr = cv_bridge::toCvShare(msg->image, msg);
// This is a shallow copy.
output_image = cv_img_ptr->image;

cv_bridge::CvImage image_cv_bridge;
image_cv_bridge.header.frame_id = "map";
image_cv_bridge.image = output_image;
publisher_.publish(image_cv_bridge.toImageMsg());

Please use the package in the repo. This also wraps some of the Eigen/TF conversions for common datatypes (Eigen::Quaterniond, Eigen::Vector3d), so it is a viable alternative to {tf,eigen}_conversions in most cases. It also transforms minkindr Transformations back and forth to both messages and TF.

Please use . This allows very easy conversions to/from ROS messages.

eigen_conversions
minkindr_conversions
ROS Documentation
tf_conversions
minkindr_conversions
ROS Documentation
minkindr_conversions
minkindr_ros
Code Documentation - Message
Code Documentation - TF
cv_bridge
ROS Tutorial
ROS Documentation