Client class for Aruco mapping. More...
#include <aruco_mapping.h>
Classes | |
struct | MarkerInfo |
Struct to keep marker information. More... | |
Public Member Functions | |
ArucoMapping (ros::NodeHandle *nh) | |
Construct a client for EZN64 USB control. | |
void | imageCallback (const sensor_msgs::ImageConstPtr &original_image) |
Callback function to handle image processing. | |
~ArucoMapping () | |
Private Member Functions | |
tf::Transform | arucoMarker2Tf (const aruco::Marker &marker) |
Compute TF from marker detector result. | |
bool | parseCalibrationFile (std::string filename) |
Function to parse data from calibration file. | |
bool | processImage (cv::Mat input_image, cv::Mat output_image) |
Process actual image, detect markers and compute poses. | |
void | publishMarker (geometry_msgs::Pose markerPose, int MarkerID, int rank) |
Function to publish all known markers for visualization purposes. | |
void | publishTfs (bool world_option) |
Function to publish all known TFs. | |
Private Attributes | |
aruco::CameraParameters | aruco_calib_params_ |
tf::TransformBroadcaster | broadcaster_ |
std::string | calib_filename_ |
int | closest_camera_index_ |
bool | first_marker_detected_ |
tf::TransformListener * | listener_ |
int | lowest_marker_id_ |
int | marker_counter_ |
int | marker_counter_previous_ |
ros::Publisher | marker_msg_pub_ |
Publisher of aruco_mapping::ArucoMarker custom message. | |
float | marker_size_ |
ros::Publisher | marker_visualization_pub_ |
Publisher of visualization_msgs::Marker message to "aruco_markers" topic. | |
std::vector< MarkerInfo > | markers_ |
Container holding MarkerInfo data about all detected markers. | |
int | num_of_markers_ |
bool | roi_allowed_ |
int | roi_h_ |
int | roi_w_ |
int | roi_x_ |
int | roi_y_ |
std::string | space_type_ |
geometry_msgs::Pose | world_position_geometry_msg_ |
Actual Pose of camera with respect to world's origin. | |
tf::StampedTransform | world_position_transform_ |
Actual TF of camera with respect to world's origin. | |
Static Private Attributes | |
static const double | BROADCAST_WAIT_INTERVAL = 0.0001 |
static const int | CV_WAIT_KEY = 10 |
static const int | CV_WINDOW_MARKER_LINE_WIDTH = 2 |
static const double | INIT_MIN_SIZE_VALUE = 1000000 |
static const double | RVIZ_MARKER_COLOR_A = 1.0 |
static const double | RVIZ_MARKER_COLOR_B = 1.0 |
static const double | RVIZ_MARKER_COLOR_G = 1.0 |
static const double | RVIZ_MARKER_COLOR_R = 1.0 |
static const double | RVIZ_MARKER_HEIGHT = 0.01 |
static const double | RVIZ_MARKER_LIFETIME = 0.2 |
static const double | THIS_IS_FIRST_MARKER = -2 |
static const double | WAIT_FOR_TRANSFORM_INTERVAL = 2.0 |
Client class for Aruco mapping.
Definition at line 67 of file aruco_mapping.h.
Construct a client for EZN64 USB control.
Definition at line 42 of file aruco_mapping.cpp.
Definition at line 108 of file aruco_mapping.cpp.
tf::Transform aruco_mapping::ArucoMapping::arucoMarker2Tf | ( | const aruco::Marker & | marker | ) | [private] |
Compute TF from marker detector result.
Definition at line 715 of file aruco_mapping.cpp.
void aruco_mapping::ArucoMapping::imageCallback | ( | const sensor_msgs::ImageConstPtr & | original_image | ) |
Callback function to handle image processing.
Definition at line 159 of file aruco_mapping.cpp.
bool aruco_mapping::ArucoMapping::parseCalibrationFile | ( | std::string | filename | ) | [private] |
Function to parse data from calibration file.
Definition at line 114 of file aruco_mapping.cpp.
bool aruco_mapping::ArucoMapping::processImage | ( | cv::Mat | input_image, |
cv::Mat | output_image | ||
) | [private] |
Process actual image, detect markers and compute poses.
Definition at line 190 of file aruco_mapping.cpp.
void aruco_mapping::ArucoMapping::publishMarker | ( | geometry_msgs::Pose | markerPose, |
int | MarkerID, | ||
int | rank | ||
) | [private] |
Function to publish all known markers for visualization purposes.
Definition at line 678 of file aruco_mapping.cpp.
void aruco_mapping::ArucoMapping::publishTfs | ( | bool | world_option | ) | [private] |
Function to publish all known TFs.
Definition at line 638 of file aruco_mapping.cpp.
Definition at line 139 of file aruco_mapping.h.
const double aruco_mapping::ArucoMapping::BROADCAST_WAIT_INTERVAL = 0.0001 [static, private] |
Definition at line 155 of file aruco_mapping.h.
Definition at line 148 of file aruco_mapping.h.
std::string aruco_mapping::ArucoMapping::calib_filename_ [private] |
Definition at line 120 of file aruco_mapping.h.
int aruco_mapping::ArucoMapping::closest_camera_index_ [private] |
Definition at line 143 of file aruco_mapping.h.
const int aruco_mapping::ArucoMapping::CV_WAIT_KEY = 10 [static, private] |
Definition at line 151 of file aruco_mapping.h.
const int aruco_mapping::ArucoMapping::CV_WINDOW_MARKER_LINE_WIDTH = 2 [static, private] |
Definition at line 152 of file aruco_mapping.h.
bool aruco_mapping::ArucoMapping::first_marker_detected_ [private] |
Definition at line 145 of file aruco_mapping.h.
const double aruco_mapping::ArucoMapping::INIT_MIN_SIZE_VALUE = 1000000 [static, private] |
Definition at line 156 of file aruco_mapping.h.
Definition at line 147 of file aruco_mapping.h.
int aruco_mapping::ArucoMapping::lowest_marker_id_ [private] |
Definition at line 144 of file aruco_mapping.h.
int aruco_mapping::ArucoMapping::marker_counter_ [private] |
Definition at line 141 of file aruco_mapping.h.
int aruco_mapping::ArucoMapping::marker_counter_previous_ [private] |
Definition at line 142 of file aruco_mapping.h.
Publisher of aruco_mapping::ArucoMarker custom message.
Definition at line 111 of file aruco_mapping.h.
float aruco_mapping::ArucoMapping::marker_size_ [private] |
Definition at line 122 of file aruco_mapping.h.
Publisher of visualization_msgs::Marker message to "aruco_markers" topic.
Definition at line 108 of file aruco_mapping.h.
std::vector<MarkerInfo> aruco_mapping::ArucoMapping::markers_ [private] |
Container holding MarkerInfo data about all detected markers.
Definition at line 131 of file aruco_mapping.h.
int aruco_mapping::ArucoMapping::num_of_markers_ [private] |
Definition at line 123 of file aruco_mapping.h.
bool aruco_mapping::ArucoMapping::roi_allowed_ [private] |
Definition at line 124 of file aruco_mapping.h.
int aruco_mapping::ArucoMapping::roi_h_ [private] |
Definition at line 128 of file aruco_mapping.h.
int aruco_mapping::ArucoMapping::roi_w_ [private] |
Definition at line 127 of file aruco_mapping.h.
int aruco_mapping::ArucoMapping::roi_x_ [private] |
Definition at line 125 of file aruco_mapping.h.
int aruco_mapping::ArucoMapping::roi_y_ [private] |
Definition at line 126 of file aruco_mapping.h.
const double aruco_mapping::ArucoMapping::RVIZ_MARKER_COLOR_A = 1.0 [static, private] |
Definition at line 163 of file aruco_mapping.h.
const double aruco_mapping::ArucoMapping::RVIZ_MARKER_COLOR_B = 1.0 [static, private] |
Definition at line 162 of file aruco_mapping.h.
const double aruco_mapping::ArucoMapping::RVIZ_MARKER_COLOR_G = 1.0 [static, private] |
Definition at line 161 of file aruco_mapping.h.
const double aruco_mapping::ArucoMapping::RVIZ_MARKER_COLOR_R = 1.0 [static, private] |
Definition at line 160 of file aruco_mapping.h.
const double aruco_mapping::ArucoMapping::RVIZ_MARKER_HEIGHT = 0.01 [static, private] |
Definition at line 158 of file aruco_mapping.h.
const double aruco_mapping::ArucoMapping::RVIZ_MARKER_LIFETIME = 0.2 [static, private] |
Definition at line 159 of file aruco_mapping.h.
std::string aruco_mapping::ArucoMapping::space_type_ [private] |
Definition at line 121 of file aruco_mapping.h.
const double aruco_mapping::ArucoMapping::THIS_IS_FIRST_MARKER = -2 [static, private] |
Definition at line 165 of file aruco_mapping.h.
const double aruco_mapping::ArucoMapping::WAIT_FOR_TRANSFORM_INTERVAL = 2.0 [static, private] |
Definition at line 154 of file aruco_mapping.h.
Actual Pose of camera with respect to world's origin.
Definition at line 137 of file aruco_mapping.h.
Actual TF of camera with respect to world's origin.
Definition at line 134 of file aruco_mapping.h.