Classes | Public Member Functions | Private Member Functions | Private Attributes | Static Private Attributes | List of all members
aruco_mapping::ArucoMapping Class Reference

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. More...
 
void imageCallback (const sensor_msgs::ImageConstPtr &original_image)
 Callback function to handle image processing. More...
 
 ~ArucoMapping ()
 

Private Member Functions

tf::Transform arucoMarker2Tf (const aruco::Marker &marker)
 Compute TF from marker detector result. More...
 
bool parseCalibrationFile (std::string filename)
 Function to parse data from calibration file. More...
 
bool processImage (cv::Mat input_image, cv::Mat output_image)
 Process actual image, detect markers and compute poses. More...
 
void publishMarker (geometry_msgs::Pose markerPose, int MarkerID, int rank)
 Function to publish all known markers for visualization purposes. More...
 
void publishTfs (bool world_option)
 Function to publish all known TFs. More...
 

Private Attributes

aruco::CameraParameters aruco_calib_params_
 
tf::TransformBroadcaster broadcaster_
 
std::string calib_filename_
 
int closest_camera_index_
 
bool first_marker_detected_
 
ros::Publisher lidar_camera_calibration_rt
 Publisher of std::vector<double> message for tvec and rvec for lidar_camera_calibration. More...
 
tf::TransformListenerlistener_
 
int lowest_marker_id_
 
int marker_counter_
 
int marker_counter_previous_
 
ros::Publisher marker_msg_pub_
 Publisher of aruco_mapping::ArucoMarker custom message. More...
 
float marker_size_
 
ros::Publisher marker_visualization_pub_
 Publisher of visualization_msgs::Marker message to "aruco_markers" topic. More...
 
std::vector< MarkerInfomarkers_
 Container holding MarkerInfo data about all detected markers. More...
 
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. More...
 
tf::StampedTransform world_position_transform_
 Actual TF of camera with respect to world's origin. More...
 

Static Private Attributes

static constexpr double BROADCAST_WAIT_INTERVAL = 0.0001
 
static const int CV_WAIT_KEY = 10
 
static const int CV_WINDOW_MARKER_LINE_WIDTH = 2
 
static constexpr double INIT_MIN_SIZE_VALUE = 1000000
 
static constexpr double RVIZ_MARKER_COLOR_A = 1.0
 
static constexpr double RVIZ_MARKER_COLOR_B = 1.0
 
static constexpr double RVIZ_MARKER_COLOR_G = 1.0
 
static constexpr double RVIZ_MARKER_COLOR_R = 1.0
 
static constexpr double RVIZ_MARKER_HEIGHT = 0.01
 
static constexpr double RVIZ_MARKER_LIFETIME = 0.2
 
static constexpr double THIS_IS_FIRST_MARKER = -2
 
static constexpr double WAIT_FOR_TRANSFORM_INTERVAL = 2.0
 

Detailed Description

Client class for Aruco mapping.

Definition at line 70 of file aruco_mapping.h.

Constructor & Destructor Documentation

aruco_mapping::ArucoMapping::ArucoMapping ( ros::NodeHandle nh)

Construct a client for EZN64 USB control.

Definition at line 43 of file aruco_mapping.cpp.

aruco_mapping::ArucoMapping::~ArucoMapping ( )

Definition at line 110 of file aruco_mapping.cpp.

Member Function Documentation

tf::Transform aruco_mapping::ArucoMapping::arucoMarker2Tf ( const aruco::Marker marker)
private

Compute TF from marker detector result.

Definition at line 749 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 161 of file aruco_mapping.cpp.

bool aruco_mapping::ArucoMapping::parseCalibrationFile ( std::string  filename)
private

Function to parse data from calibration file.

Definition at line 116 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 194 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 712 of file aruco_mapping.cpp.

void aruco_mapping::ArucoMapping::publishTfs ( bool  world_option)
private

Function to publish all known TFs.

Definition at line 672 of file aruco_mapping.cpp.

Member Data Documentation

aruco::CameraParameters aruco_mapping::ArucoMapping::aruco_calib_params_
private

Definition at line 145 of file aruco_mapping.h.

constexpr double aruco_mapping::ArucoMapping::BROADCAST_WAIT_INTERVAL = 0.0001
staticprivate

Definition at line 161 of file aruco_mapping.h.

tf::TransformBroadcaster aruco_mapping::ArucoMapping::broadcaster_
private

Definition at line 154 of file aruco_mapping.h.

std::string aruco_mapping::ArucoMapping::calib_filename_
private

Definition at line 126 of file aruco_mapping.h.

int aruco_mapping::ArucoMapping::closest_camera_index_
private

Definition at line 149 of file aruco_mapping.h.

const int aruco_mapping::ArucoMapping::CV_WAIT_KEY = 10
staticprivate

Definition at line 157 of file aruco_mapping.h.

const int aruco_mapping::ArucoMapping::CV_WINDOW_MARKER_LINE_WIDTH = 2
staticprivate

Definition at line 158 of file aruco_mapping.h.

bool aruco_mapping::ArucoMapping::first_marker_detected_
private

Definition at line 151 of file aruco_mapping.h.

constexpr double aruco_mapping::ArucoMapping::INIT_MIN_SIZE_VALUE = 1000000
staticprivate

Definition at line 162 of file aruco_mapping.h.

ros::Publisher aruco_mapping::ArucoMapping::lidar_camera_calibration_rt
private

Publisher of std::vector<double> message for tvec and rvec for lidar_camera_calibration.

Definition at line 117 of file aruco_mapping.h.

tf::TransformListener* aruco_mapping::ArucoMapping::listener_
private

Definition at line 153 of file aruco_mapping.h.

int aruco_mapping::ArucoMapping::lowest_marker_id_
private

Definition at line 150 of file aruco_mapping.h.

int aruco_mapping::ArucoMapping::marker_counter_
private

Definition at line 147 of file aruco_mapping.h.

int aruco_mapping::ArucoMapping::marker_counter_previous_
private

Definition at line 148 of file aruco_mapping.h.

ros::Publisher aruco_mapping::ArucoMapping::marker_msg_pub_
private

Publisher of aruco_mapping::ArucoMarker custom message.

Definition at line 114 of file aruco_mapping.h.

float aruco_mapping::ArucoMapping::marker_size_
private

Definition at line 128 of file aruco_mapping.h.

ros::Publisher aruco_mapping::ArucoMapping::marker_visualization_pub_
private

Publisher of visualization_msgs::Marker message to "aruco_markers" topic.

Definition at line 111 of file aruco_mapping.h.

std::vector<MarkerInfo> aruco_mapping::ArucoMapping::markers_
private

Container holding MarkerInfo data about all detected markers.

Definition at line 137 of file aruco_mapping.h.

int aruco_mapping::ArucoMapping::num_of_markers_
private

Definition at line 129 of file aruco_mapping.h.

bool aruco_mapping::ArucoMapping::roi_allowed_
private

Definition at line 130 of file aruco_mapping.h.

int aruco_mapping::ArucoMapping::roi_h_
private

Definition at line 134 of file aruco_mapping.h.

int aruco_mapping::ArucoMapping::roi_w_
private

Definition at line 133 of file aruco_mapping.h.

int aruco_mapping::ArucoMapping::roi_x_
private

Definition at line 131 of file aruco_mapping.h.

int aruco_mapping::ArucoMapping::roi_y_
private

Definition at line 132 of file aruco_mapping.h.

constexpr double aruco_mapping::ArucoMapping::RVIZ_MARKER_COLOR_A = 1.0
staticprivate

Definition at line 169 of file aruco_mapping.h.

constexpr double aruco_mapping::ArucoMapping::RVIZ_MARKER_COLOR_B = 1.0
staticprivate

Definition at line 168 of file aruco_mapping.h.

constexpr double aruco_mapping::ArucoMapping::RVIZ_MARKER_COLOR_G = 1.0
staticprivate

Definition at line 167 of file aruco_mapping.h.

constexpr double aruco_mapping::ArucoMapping::RVIZ_MARKER_COLOR_R = 1.0
staticprivate

Definition at line 166 of file aruco_mapping.h.

constexpr double aruco_mapping::ArucoMapping::RVIZ_MARKER_HEIGHT = 0.01
staticprivate

Definition at line 164 of file aruco_mapping.h.

constexpr double aruco_mapping::ArucoMapping::RVIZ_MARKER_LIFETIME = 0.2
staticprivate

Definition at line 165 of file aruco_mapping.h.

std::string aruco_mapping::ArucoMapping::space_type_
private

Definition at line 127 of file aruco_mapping.h.

constexpr double aruco_mapping::ArucoMapping::THIS_IS_FIRST_MARKER = -2
staticprivate

Definition at line 171 of file aruco_mapping.h.

constexpr double aruco_mapping::ArucoMapping::WAIT_FOR_TRANSFORM_INTERVAL = 2.0
staticprivate

Definition at line 160 of file aruco_mapping.h.

geometry_msgs::Pose aruco_mapping::ArucoMapping::world_position_geometry_msg_
private

Actual Pose of camera with respect to world's origin.

Definition at line 143 of file aruco_mapping.h.

tf::StampedTransform aruco_mapping::ArucoMapping::world_position_transform_
private

Actual TF of camera with respect to world's origin.

Definition at line 140 of file aruco_mapping.h.


The documentation for this class was generated from the following files:


lidar_camera_calibration
Author(s):
autogenerated on Sat Feb 6 2021 03:39:37