Public Member Functions | Private Member Functions | Private Attributes
rail_object_detector::DarknetDetector Class Reference

#include <darknet_detector.h>

List of all members.

Public Member Functions

void backgroundDetectionCallback (const ros::TimerEvent &e)
 DarknetDetector (ros::NodeHandle &handle, ros::NodeHandle &private_handle)
bool imageQueryCallback (ImageQuery::Request &req, ImageQuery::Response &res)
void imageSubscriberCallback (const sensor_msgs::ImageConstPtr &msg)
void runBackgroundDetections ()
bool sceneQueryCallback (SceneQuery::Request &req, SceneQuery::Response &res)
bool start ()
bool stop ()

Private Member Functions

bool detectObjects (cv_bridge::CvImagePtr cv_ptr, std::vector< Object > &detected_objects)

Private Attributes

char ** class_names_
ros::Publisher detections_pub_
boost::thread * detections_thread_
ros::CallbackQueuePtr image_callback_q_
ros::ServiceServer image_query_server_
boost::shared_ptr
< ros::AsyncSpinner
image_spinner_
image_transport::Subscriber image_sub_
image_transport::ImageTransport it_
sensor_msgs::ImageConstPtr latest_image_
float max_desired_publish_freq_
boost::mutex mutex_
network net_
ros::NodeHandle nh_
bool perform_detections_
ros::NodeHandle private_nh_
float probability_threshold_
bool publish_detections_topic_
ros::CallbackQueuePtr scene_callback_q_
ros::ServiceServer scene_query_server_
boost::shared_ptr
< ros::AsyncSpinner
scene_spinner_
bool use_image_service_
bool use_scene_service_

Detailed Description

Definition at line 111 of file darknet_detector.h.


Constructor & Destructor Documentation

Definition at line 115 of file darknet_detector.h.


Member Function Documentation

Callback function for the background publisher which is called back on a timer depending on the desired frequency of detections

Definition at line 328 of file darknet_detector.cpp.

bool DarknetDetector::detectObjects ( cv_bridge::CvImagePtr  cv_ptr,
std::vector< Object > &  detected_objects 
) [private]

Common method that calls the darknet network for the set of objects. The method takes as arguments an OpenCV image pointer and a reference to a std::vector that the detected objects can be inserted into. It returns a status of true if there was no issue in detection; else it returns false.

Definition at line 222 of file darknet_detector.cpp.

bool DarknetDetector::imageQueryCallback ( ImageQuery::Request &  req,
ImageQuery::Response &  res 
)

Callback for an image query

Definition at line 297 of file darknet_detector.cpp.

void DarknetDetector::imageSubscriberCallback ( const sensor_msgs::ImageConstPtr &  msg)

Callback for the images coming in on the image topic

Definition at line 209 of file darknet_detector.cpp.

Runnable function that performs detections in the background and publishes them to the detections topic. (Callback)

Definition at line 366 of file darknet_detector.cpp.

bool DarknetDetector::sceneQueryCallback ( SceneQuery::Request &  req,
SceneQuery::Response &  res 
)

Callback for a scene query

Definition at line 257 of file darknet_detector.cpp.

Start the detector

Definition at line 27 of file darknet_detector.cpp.

Stop the detector

Definition at line 162 of file darknet_detector.cpp.


Member Data Documentation

Definition at line 198 of file darknet_detector.h.

Definition at line 175 of file darknet_detector.h.

Definition at line 192 of file darknet_detector.h.

Definition at line 187 of file darknet_detector.h.

Definition at line 177 of file darknet_detector.h.

Definition at line 189 of file darknet_detector.h.

Definition at line 174 of file darknet_detector.h.

Definition at line 173 of file darknet_detector.h.

sensor_msgs::ImageConstPtr rail_object_detector::DarknetDetector::latest_image_ [private]

Definition at line 183 of file darknet_detector.h.

Definition at line 170 of file darknet_detector.h.

Definition at line 180 of file darknet_detector.h.

Definition at line 197 of file darknet_detector.h.

Definition at line 161 of file darknet_detector.h.

Definition at line 193 of file darknet_detector.h.

Definition at line 162 of file darknet_detector.h.

Definition at line 196 of file darknet_detector.h.

Definition at line 167 of file darknet_detector.h.

Definition at line 186 of file darknet_detector.h.

Definition at line 176 of file darknet_detector.h.

Definition at line 188 of file darknet_detector.h.

Definition at line 166 of file darknet_detector.h.

Definition at line 165 of file darknet_detector.h.


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


rail_object_detector
Author(s):
autogenerated on Sat Jun 8 2019 20:26:31