Public Member Functions | Private Member Functions | Private Attributes | List of all members
rc_tagdetect_client::RosTagdetectClient Class Reference

#include <ros_tagdetect_client.h>

Public Member Functions

 RosTagdetectClient (const std::string &host, const ros::NodeHandle &nh, const std::string &detection_type)
 
 ~RosTagdetectClient ()
 

Private Member Functions

void advertiseServicesAndTopics ()
 
template<typename Request , typename Response >
bool callService (const std::string &name, const Request &req, Response &res)
 
bool detect (rc_tagdetect_client::DetectTagsRequest &req, rc_tagdetect_client::DetectTagsResponse &response)
 
bool detectService (rc_tagdetect_client::DetectTagsRequest &request, rc_tagdetect_client::DetectTagsResponse &response)
 
void dynamicReconfigureCallback (rc_tagdetect_client::TagDetectConfig &config, uint32_t)
 
void initConfiguration ()
 
bool startContinousDetection (rc_tagdetect_client::StartContinuousDetectionRequest &request, rc_tagdetect_client::StartContinuousDetectionResponse &response)
 
void startTagDetect ()
 
bool stopContinousDetection (std_srvs::TriggerRequest &request, std_srvs::TriggerResponse &response)
 
void stopTagDetect ()
 

Private Attributes

std::thread continuous_mode_thread_
 
ros::Publisher detections_pub_
 
std::tuple< size_t, size_t, size_timage_version_
 
ros::NodeHandle nh_
 
std::unique_ptr< rc_rest_api::RestHelperrest_helper_
 
std::unique_ptr< dynamic_reconfigure::Server< rc_tagdetect_client::TagDetectConfig > > server_
 
ros::ServiceServer srv_detect_
 
ros::ServiceServer srv_start_continuous_detection_
 
ros::ServiceServer srv_stop_continuous_detection_
 
std::atomic_bool stop_continuous_mode_thread_
 
std::unique_ptr< rc_tagdetect_client::Visualizationvisualizer_
 

Detailed Description

Definition at line 55 of file ros_tagdetect_client.h.

Constructor & Destructor Documentation

rc_tagdetect_client::RosTagdetectClient::RosTagdetectClient ( const std::string &  host,
const ros::NodeHandle nh,
const std::string &  detection_type 
)

Definition at line 40 of file ros_tagdetect_client.cpp.

rc_tagdetect_client::RosTagdetectClient::~RosTagdetectClient ( )

Definition at line 59 of file ros_tagdetect_client.cpp.

Member Function Documentation

void rc_tagdetect_client::RosTagdetectClient::advertiseServicesAndTopics ( )
private

Definition at line 200 of file ros_tagdetect_client.cpp.

template<typename Request , typename Response >
bool rc_tagdetect_client::RosTagdetectClient::callService ( const std::string &  name,
const Request &  req,
Response &  res 
)
private

Definition at line 92 of file ros_tagdetect_client.cpp.

bool rc_tagdetect_client::RosTagdetectClient::detect ( rc_tagdetect_client::DetectTagsRequest &  req,
rc_tagdetect_client::DetectTagsResponse &  response 
)
private

Definition at line 117 of file ros_tagdetect_client.cpp.

bool rc_tagdetect_client::RosTagdetectClient::detectService ( rc_tagdetect_client::DetectTagsRequest &  request,
rc_tagdetect_client::DetectTagsResponse &  response 
)
private

Definition at line 128 of file ros_tagdetect_client.cpp.

void rc_tagdetect_client::RosTagdetectClient::dynamicReconfigureCallback ( rc_tagdetect_client::TagDetectConfig &  config,
uint32_t   
)
private

Definition at line 270 of file ros_tagdetect_client.cpp.

void rc_tagdetect_client::RosTagdetectClient::initConfiguration ( )
private

Definition at line 240 of file ros_tagdetect_client.cpp.

bool rc_tagdetect_client::RosTagdetectClient::startContinousDetection ( rc_tagdetect_client::StartContinuousDetectionRequest &  request,
rc_tagdetect_client::StartContinuousDetectionResponse &  response 
)
private

Definition at line 153 of file ros_tagdetect_client.cpp.

void rc_tagdetect_client::RosTagdetectClient::startTagDetect ( )
private

Definition at line 81 of file ros_tagdetect_client.cpp.

bool rc_tagdetect_client::RosTagdetectClient::stopContinousDetection ( std_srvs::TriggerRequest &  request,
std_srvs::TriggerResponse &  response 
)
private

Definition at line 142 of file ros_tagdetect_client.cpp.

void rc_tagdetect_client::RosTagdetectClient::stopTagDetect ( )
private

Definition at line 86 of file ros_tagdetect_client.cpp.

Member Data Documentation

std::thread rc_tagdetect_client::RosTagdetectClient::continuous_mode_thread_
private

Definition at line 97 of file ros_tagdetect_client.h.

ros::Publisher rc_tagdetect_client::RosTagdetectClient::detections_pub_
private

Definition at line 95 of file ros_tagdetect_client.h.

std::tuple<size_t, size_t, size_t> rc_tagdetect_client::RosTagdetectClient::image_version_
private

Definition at line 104 of file ros_tagdetect_client.h.

ros::NodeHandle rc_tagdetect_client::RosTagdetectClient::nh_
private

Definition at line 90 of file ros_tagdetect_client.h.

std::unique_ptr<rc_rest_api::RestHelper> rc_tagdetect_client::RosTagdetectClient::rest_helper_
private

Definition at line 101 of file ros_tagdetect_client.h.

std::unique_ptr<dynamic_reconfigure::Server<rc_tagdetect_client::TagDetectConfig> > rc_tagdetect_client::RosTagdetectClient::server_
private

Definition at line 100 of file ros_tagdetect_client.h.

ros::ServiceServer rc_tagdetect_client::RosTagdetectClient::srv_detect_
private

Definition at line 91 of file ros_tagdetect_client.h.

ros::ServiceServer rc_tagdetect_client::RosTagdetectClient::srv_start_continuous_detection_
private

Definition at line 92 of file ros_tagdetect_client.h.

ros::ServiceServer rc_tagdetect_client::RosTagdetectClient::srv_stop_continuous_detection_
private

Definition at line 93 of file ros_tagdetect_client.h.

std::atomic_bool rc_tagdetect_client::RosTagdetectClient::stop_continuous_mode_thread_
private

Definition at line 98 of file ros_tagdetect_client.h.

std::unique_ptr<rc_tagdetect_client::Visualization> rc_tagdetect_client::RosTagdetectClient::visualizer_
private

Definition at line 102 of file ros_tagdetect_client.h.


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


rc_tagdetect_client
Author(s): Monika Florek-Jasinska , Raphael Schaller
autogenerated on Sat Feb 13 2021 03:42:18