Main Page
Namespaces
Classes
Files
File List
File Members
include
aruco_ros
aruco_ros_utils.h
Go to the documentation of this file.
1
#ifndef ARUCO_ROS_UTILS_H
2
#define ARUCO_ROS_UTILS_H
3
4
#include <
aruco/aruco.h
>
5
#include <sensor_msgs/CameraInfo.h>
6
#include <
tf/transform_datatypes.h
>
7
8
namespace
aruco_ros
9
{
18
aruco::CameraParameters
rosCameraInfo2ArucoCamParams
(
const
sensor_msgs::CameraInfo& cam_info,
19
bool
useRectifiedParameters);
20
21
//FIXME: make parameter const as soon as the used function is also const
22
tf::Transform
arucoMarker2Tf
(
const
aruco::Marker
& marker,
bool
rotate_marker_axis=
true
);
23
24
}
25
#endif // ARUCO_ROS_UTILS_H
transform_datatypes.h
aruco.h
aruco_ros
Definition:
aruco_ros_utils.h:8
aruco_ros::arucoMarker2Tf
tf::Transform arucoMarker2Tf(const aruco::Marker &marker, bool rotate_marker_axis=true)
Definition:
aruco_ros_utils.cpp:45
tf::Transform
aruco::Marker
aruco_ros::rosCameraInfo2ArucoCamParams
aruco::CameraParameters rosCameraInfo2ArucoCamParams(const sensor_msgs::CameraInfo &cam_info, bool useRectifiedParameters)
rosCameraInfo2ArucoCamParams gets the camera intrinsics from a CameraInfo message and copies them to ...
Definition:
aruco_ros_utils.cpp:7
aruco::CameraParameters
aruco_ros
Author(s): Rafael Muñoz Salinas
, Bence Magyar
autogenerated on Wed Sep 2 2020 04:02:14