◆ ObjectDetectionVisualizer()
ObjectDetectionVisualizer::ObjectDetectionVisualizer |
( |
ros::NodeHandle & |
nh | ) |
|
|
inline |
◆ ~ObjectDetectionVisualizer()
ObjectDetectionVisualizer::~ObjectDetectionVisualizer |
( |
| ) |
|
|
inline |
◆ convertImageMessageToMat()
bool ObjectDetectionVisualizer::convertImageMessageToMat |
( |
const sensor_msgs::Image::ConstPtr & |
image_msg, |
|
|
cv_bridge::CvImageConstPtr & |
image_ptr, |
|
|
cv::Mat & |
image |
|
) |
| |
|
inlineprivate |
◆ convertPclMessageToMat()
bool ObjectDetectionVisualizer::convertPclMessageToMat |
( |
const sensor_msgs::PointCloud2::ConstPtr & |
pointcloud_msg, |
|
|
pcl::PointCloud< pcl::PointXYZRGB > & |
pointcloud, |
|
|
cv::Mat & |
color_image |
|
) |
| |
|
inlineprivate |
◆ detectionImageCallback()
void ObjectDetectionVisualizer::detectionImageCallback |
( |
const cob_object_detection_msgs::DetectionArray::ConstPtr & |
object_detection_msg, |
|
|
const sensor_msgs::PointCloud2::ConstPtr & |
pointcloud_msg |
|
) |
| |
|
inlineprivate |
◆ drawDetectedModel3D()
bool ObjectDetectionVisualizer::drawDetectedModel3D |
( |
cv::Mat |
image, |
|
|
const std::vector< cv::Point > & |
corners_2d, |
|
|
const cv::Scalar & |
color |
|
) |
| |
|
inlineprivate |
◆ objectDetectionArrayCallback()
void ObjectDetectionVisualizer::objectDetectionArrayCallback |
( |
const cob_object_detection_msgs::DetectionArray::ConstPtr & |
object_detection_msg | ) |
|
|
inlineprivate |
◆ objectDetectionDisplayCallback()
void ObjectDetectionVisualizer::objectDetectionDisplayCallback |
( |
const cob_object_detection_msgs::DetectionArray::ConstPtr & |
object_detection_msg | ) |
|
|
inlineprivate |
◆ pointcloudCallback()
void ObjectDetectionVisualizer::pointcloudCallback |
( |
const sensor_msgs::PointCloud2::ConstPtr & |
pointcloud_msg | ) |
|
|
inlineprivate |
◆ pointcloudInfoCallback()
void ObjectDetectionVisualizer::pointcloudInfoCallback |
( |
const sensor_msgs::CameraInfoConstPtr & |
data | ) |
|
|
inlineprivate |
◆ projectPoint()
cv::Point ObjectDetectionVisualizer::projectPoint |
( |
const cv::Vec3d & |
point_3d | ) |
|
|
inlineprivate |
◆ renderDetections()
bool ObjectDetectionVisualizer::renderDetections |
( |
cv::Mat & |
image, |
|
|
const cob_object_detection_msgs::DetectionArray::ConstPtr & |
object_detection_msg |
|
) |
| |
|
inlineprivate |
◆ color_image_
cv::Mat ObjectDetectionVisualizer::color_image_ |
|
private |
◆ color_image_mutex_
boost::mutex ObjectDetectionVisualizer::color_image_mutex_ |
|
private |
◆ detection_array_sub_
◆ display_detection_image_
bool ObjectDetectionVisualizer::display_detection_image_ |
|
private |
◆ display_rviz_markers_
bool ObjectDetectionVisualizer::display_rviz_markers_ |
|
private |
◆ image_counter_
int ObjectDetectionVisualizer::image_counter_ |
|
private |
◆ marker_array_msg_
visualization_msgs::MarkerArray ObjectDetectionVisualizer::marker_array_msg_ |
|
private |
◆ marker_array_publisher_
◆ node_handle_
◆ object_name_to_color_map_
std::map<std::string, cv::Scalar> ObjectDetectionVisualizer::object_name_to_color_map_ |
|
private |
◆ pointcloud_info_sub_
◆ pointcloud_sub_
◆ prev_marker_array_size_
unsigned int ObjectDetectionVisualizer::prev_marker_array_size_ |
|
private |
◆ projection_matrix_
cv::Mat ObjectDetectionVisualizer::projection_matrix_ |
|
private |
◆ projection_matrix_received_
bool ObjectDetectionVisualizer::projection_matrix_received_ |
|
private |
The documentation for this class was generated from the following file: