Public Member Functions | Private Member Functions | Private Attributes | List of all members
aruco_marker_recognition::ArucoMarkerRecognition Class Reference

This is the base class of the marker recognition system used for creating the ros environment and controlling the recognition processes. More...

#include <aruco_marker_recognition.h>

Public Member Functions

 ArucoMarkerRecognition ()
 The constructor of this class. More...
 

Private Member Functions

void configCallback (ArucoMarkerRecognitionConfig &config_, uint32_t level)
 The callback function which is called when the configuration file has changed. More...
 
visualization_msgs::Marker createArrowMarker (int id, const geometry_msgs::Pose &pose, const string &frame_id, bool isNsX=false)
 Create a ros marker from a given pose of a found marker. More...
 
asr_msgs::AsrObject createAsrObject (const geometry_msgs::Pose &pose, const std::string &object_type, const string &frame_id, const std::string &mesh_res="")
 Create a asr_object from a given marker pose. More...
 
visualization_msgs::Marker createMeshMarker (int id, const geometry_msgs::Pose &pose, const std::string &mesh_res, const string &frame_id)
 Create a ros marker from a given pose of a found marker. More...
 
visualization_msgs::Marker createSquareMarker (int id, const geometry_msgs::Pose &pose, const string &frame_id)
 Create a ros marker from a given pose of a found marker. More...
 
cv::Mat drawMarkers (const cv::Mat &image, const std::vector< aruco::Marker > &markers)
 Draws recognized markers and their id into an image. More...
 
std::map< int, geometry_msgs::Pose > getMarkerPoses (const std::vector< aruco::Marker > &left_markers)
 
std::map< int, geometry_msgs::Pose > getMarkerPoses (const std::vector< aruco::Marker > &left_markers, const std::vector< aruco::Marker > &right_markers, const ivt_bridge::IvtStereoCalibration &ivtCalib)
 Calculates poses from corresponding found markers of the right and left image. More...
 
void imageCallback (const sensor_msgs::ImageConstPtr &input_img_left, const sensor_msgs::ImageConstPtr &input_img_right, const sensor_msgs::CameraInfoConstPtr &cam_info_left, const sensor_msgs::CameraInfoConstPtr &cam_info_right)
 The ros callback which is called when new images are received. More...
 
bool processGetRecognizerRequest (GetRecognizer::Request &req, GetRecognizer::Response &res)
 
bool processReleaseRecognizerRequest (ReleaseRecognizer::Request &req, ReleaseRecognizer::Response &res)
 

Private Attributes

ros::Publisher asr_objects_pub_
 
ArucoMarkerRecognitionConfig config_
 
MarkerDetection detector_
 
ros::ServiceServer get_recognizer_service_
 
std::string image_left_cam_info_topic_
 
message_filters::Subscriber< sensor_msgs::CameraInfo > image_left_param_sub_
 
message_filters::Subscriber< sensor_msgs::Image > image_left_sub_
 
std::string image_left_topic_
 
std::string image_right_cam_info_topic_
 
message_filters::Subscriber< sensor_msgs::CameraInfo > image_right_param_sub_
 
message_filters::Subscriber< sensor_msgs::Image > image_right_sub_
 
std::string image_right_topic_
 
ros::Publisher left_markers_img_pub_
 
double marker_size_
 
ros::NodeHandle nh_
 
ros::ServiceClient object_mesh_service_client_
 
bool recognition_paused_
 
std::string recognizer_name_
 
dynamic_reconfigure::Server< ArucoMarkerRecognitionConfig > reconfigure_server_
 
ros::ServiceServer release_recognizer_service_
 
ros::Publisher right_markers_img_pub_
 
boost::shared_ptr< ApproximateSyncsync_policy_
 
bool use_stereo_
 
ros::Publisher vis_markers_pub_
 

Detailed Description

This is the base class of the marker recognition system used for creating the ros environment and controlling the recognition processes.

Definition at line 62 of file aruco_marker_recognition.h.

Constructor & Destructor Documentation

aruco_marker_recognition::ArucoMarkerRecognition::ArucoMarkerRecognition ( )

The constructor of this class.

Definition at line 32 of file aruco_marker_recognition.cpp.

Member Function Documentation

void aruco_marker_recognition::ArucoMarkerRecognition::configCallback ( ArucoMarkerRecognitionConfig &  config_,
uint32_t  level 
)
private

The callback function which is called when the configuration file has changed.

Parameters
configThe updated configuration
levelThe level which is the result of ORing together all of level values of the parameters that have changed

Definition at line 183 of file aruco_marker_recognition.cpp.

visualization_msgs::Marker aruco_marker_recognition::ArucoMarkerRecognition::createArrowMarker ( int  id,
const geometry_msgs::Pose &  pose,
const string &  frame_id,
bool  isNsX = false 
)
private

Create a ros marker from a given pose of a found marker.

Parameters
idThe id of the found marker
poseThe pose of the found marker
frame_idThe id of the frame the marker pose is relative to
isNsXDetermine if the ns is a "X" ns or not
Returns
The created ros marker

Definition at line 346 of file aruco_marker_recognition.cpp.

asr_msgs::AsrObject aruco_marker_recognition::ArucoMarkerRecognition::createAsrObject ( const geometry_msgs::Pose &  pose,
const std::string &  object_type,
const string &  frame_id,
const std::string &  mesh_res = "" 
)
private

Create a asr_object from a given marker pose.

Parameters
poseThe pose of the marker
object_typeThe type of the object corresponding to the found marker provided by the object_database
frame_idThe id of the frame the marker pose is relative to
mesh_resThe markers' corresponding mesh resource provided by the object_database
Returns
The created asr_object

Definition at line 400 of file aruco_marker_recognition.cpp.

visualization_msgs::Marker aruco_marker_recognition::ArucoMarkerRecognition::createMeshMarker ( int  id,
const geometry_msgs::Pose &  pose,
const std::string &  mesh_res,
const string &  frame_id 
)
private

Create a ros marker from a given pose of a found marker.

Parameters
idThe id of the found marker
poseThe pose of the found marker
mesh_resThe markers' corresponding mesh resource provided by the object_database
frame_idThe id of the frame the marker pose is relative to
Returns
The created ros marker

Definition at line 377 of file aruco_marker_recognition.cpp.

visualization_msgs::Marker aruco_marker_recognition::ArucoMarkerRecognition::createSquareMarker ( int  id,
const geometry_msgs::Pose &  pose,
const string &  frame_id 
)
private

Create a ros marker from a given pose of a found marker.

Parameters
idThe id of the found marker
poseThe pose of the found marker
frame_idThe id of the frame the marker pose is relative to
Returns
The created ros marker

Definition at line 325 of file aruco_marker_recognition.cpp.

cv::Mat aruco_marker_recognition::ArucoMarkerRecognition::drawMarkers ( const cv::Mat &  image,
const std::vector< aruco::Marker > &  markers 
)
private

Draws recognized markers and their id into an image.

Parameters
imageThe image to draw the markers into
markersThe markers to draw
Returns
The input image with the drawn markers

Definition at line 187 of file aruco_marker_recognition.cpp.

std::map< int, geometry_msgs::Pose > aruco_marker_recognition::ArucoMarkerRecognition::getMarkerPoses ( const std::vector< aruco::Marker > &  left_markers)
private

Definition at line 195 of file aruco_marker_recognition.cpp.

std::map< int, geometry_msgs::Pose > aruco_marker_recognition::ArucoMarkerRecognition::getMarkerPoses ( const std::vector< aruco::Marker > &  left_markers,
const std::vector< aruco::Marker > &  right_markers,
const ivt_bridge::IvtStereoCalibration &  ivtCalib 
)
private

Calculates poses from corresponding found markers of the right and left image.

Parameters
left_markersThe markers found in the left image
right_markersThe markers found in the right image
ivtCalibThe calibration information of the used stereo camera system
Returns
A map containing pairs of marker ids and their found poses

Definition at line 237 of file aruco_marker_recognition.cpp.

void aruco_marker_recognition::ArucoMarkerRecognition::imageCallback ( const sensor_msgs::ImageConstPtr &  input_img_left,
const sensor_msgs::ImageConstPtr &  input_img_right,
const sensor_msgs::CameraInfoConstPtr &  cam_info_left,
const sensor_msgs::CameraInfoConstPtr &  cam_info_right 
)
private

The ros callback which is called when new images are received.

Parameters
input_img_leftThe image of the left camera
input_img_rightThe image of the right camera
cam_info_leftThe camera parameters of the left camera
cam_info_rightThe camera parameters of the right camera

Definition at line 107 of file aruco_marker_recognition.cpp.

bool aruco_marker_recognition::ArucoMarkerRecognition::processGetRecognizerRequest ( GetRecognizer::Request &  req,
GetRecognizer::Response &  res 
)
private

Processes the request to recognize markers

Parameters
reqThe request message
resThe correlated response message
Returns
True, to indicate that the request was successful

Definition at line 93 of file aruco_marker_recognition.cpp.

bool aruco_marker_recognition::ArucoMarkerRecognition::processReleaseRecognizerRequest ( ReleaseRecognizer::Request &  req,
ReleaseRecognizer::Response &  res 
)
private

Processes the request to stop the marker recognition

Parameters
reqThe request message
resThe correlated response message
Returns
True, to indicate that the request was successful

Definition at line 100 of file aruco_marker_recognition.cpp.

Member Data Documentation

ros::Publisher aruco_marker_recognition::ArucoMarkerRecognition::asr_objects_pub_
private

Definition at line 116 of file aruco_marker_recognition.h.

ArucoMarkerRecognitionConfig aruco_marker_recognition::ArucoMarkerRecognition::config_
private

The configuration file containing the dynamic parameters of this system

Definition at line 101 of file aruco_marker_recognition.h.

MarkerDetection aruco_marker_recognition::ArucoMarkerRecognition::detector_
private

The detector used to recognize the markers in an image

Definition at line 110 of file aruco_marker_recognition.h.

ros::ServiceServer aruco_marker_recognition::ArucoMarkerRecognition::get_recognizer_service_
private

The servers of the provided services

Definition at line 94 of file aruco_marker_recognition.h.

std::string aruco_marker_recognition::ArucoMarkerRecognition::image_left_cam_info_topic_
private

The topic of the left camera parameters

Definition at line 76 of file aruco_marker_recognition.h.

message_filters::Subscriber<sensor_msgs::CameraInfo> aruco_marker_recognition::ArucoMarkerRecognition::image_left_param_sub_
private

Definition at line 90 of file aruco_marker_recognition.h.

message_filters::Subscriber<sensor_msgs::Image> aruco_marker_recognition::ArucoMarkerRecognition::image_left_sub_
private

The ros subscribers

Definition at line 88 of file aruco_marker_recognition.h.

std::string aruco_marker_recognition::ArucoMarkerRecognition::image_left_topic_
private

The topic of the left camera image

Definition at line 70 of file aruco_marker_recognition.h.

std::string aruco_marker_recognition::ArucoMarkerRecognition::image_right_cam_info_topic_
private

The topic of the right camera parameters

Definition at line 79 of file aruco_marker_recognition.h.

message_filters::Subscriber<sensor_msgs::CameraInfo> aruco_marker_recognition::ArucoMarkerRecognition::image_right_param_sub_
private

Definition at line 91 of file aruco_marker_recognition.h.

message_filters::Subscriber<sensor_msgs::Image> aruco_marker_recognition::ArucoMarkerRecognition::image_right_sub_
private

Definition at line 89 of file aruco_marker_recognition.h.

std::string aruco_marker_recognition::ArucoMarkerRecognition::image_right_topic_
private

The topic of the right camera image

Definition at line 73 of file aruco_marker_recognition.h.

ros::Publisher aruco_marker_recognition::ArucoMarkerRecognition::left_markers_img_pub_
private

The ros publishers

Definition at line 113 of file aruco_marker_recognition.h.

double aruco_marker_recognition::ArucoMarkerRecognition::marker_size_
private

The size of the used markers in meters

Definition at line 85 of file aruco_marker_recognition.h.

ros::NodeHandle aruco_marker_recognition::ArucoMarkerRecognition::nh_
private

Ros' interface for creating subscribers, publishers, etc.

Definition at line 82 of file aruco_marker_recognition.h.

ros::ServiceClient aruco_marker_recognition::ArucoMarkerRecognition::object_mesh_service_client_
private

The client used to contact the object database service

Definition at line 104 of file aruco_marker_recognition.h.

bool aruco_marker_recognition::ArucoMarkerRecognition::recognition_paused_
private

A bool value indicating whether the recognition is paused or running

Definition at line 122 of file aruco_marker_recognition.h.

std::string aruco_marker_recognition::ArucoMarkerRecognition::recognizer_name_
private

The name of this recognizer

Definition at line 119 of file aruco_marker_recognition.h.

dynamic_reconfigure::Server<ArucoMarkerRecognitionConfig> aruco_marker_recognition::ArucoMarkerRecognition::reconfigure_server_
private

Dynamic reconfigure server which keeps track of the callback function

Definition at line 98 of file aruco_marker_recognition.h.

ros::ServiceServer aruco_marker_recognition::ArucoMarkerRecognition::release_recognizer_service_
private

Definition at line 95 of file aruco_marker_recognition.h.

ros::Publisher aruco_marker_recognition::ArucoMarkerRecognition::right_markers_img_pub_
private

Definition at line 114 of file aruco_marker_recognition.h.

boost::shared_ptr<ApproximateSync> aruco_marker_recognition::ArucoMarkerRecognition::sync_policy_
private

The policy the subscribers are synced with

Definition at line 107 of file aruco_marker_recognition.h.

bool aruco_marker_recognition::ArucoMarkerRecognition::use_stereo_
private

Definition at line 67 of file aruco_marker_recognition.h.

ros::Publisher aruco_marker_recognition::ArucoMarkerRecognition::vis_markers_pub_
private

Definition at line 115 of file aruco_marker_recognition.h.


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


asr_aruco_marker_recognition
Author(s): Allgeyer Tobias, Meißner Pascal, Qattan Mohamad
autogenerated on Mon Jun 10 2019 12:40:22