Public Member Functions | Protected Member Functions | Private Attributes | List of all members
rc_silhouettematch_client::SilhouetteMatchClient Class Reference

#include <rc_silhouettematch_client.h>

Public Member Functions

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

Protected Member Functions

bool calibrateBasePlane (CalibrateBasePlane::Request &req, CalibrateBasePlane::Response &res)
 
template<typename Request , typename Response >
bool callService (const std::string &name, const Request &req, Response &res)
 
bool deleteBasePlaneCalib (DeleteBasePlaneCalibration::Request &req, DeleteBasePlaneCalibration::Response &res)
 
bool deleteROIs (DeleteRegionsOfInterest::Request &req, DeleteRegionsOfInterest::Response &res)
 
bool detectObject (DetectObject::Request &req, DetectObject::Response &res)
 
bool getBasePlaneCalib (GetBasePlaneCalibration::Request &req, GetBasePlaneCalibration::Response &res)
 
bool getROIs (GetRegionsOfInterest::Request &req, GetRegionsOfInterest::Response &res)
 
void initParameters ()
 
bool setROI (SetRegionOfInterest::Request &req, SetRegionOfInterest::Response &res)
 
void updateParameters (SilhouetteMatchConfig &config, uint32_t)
 

Private Attributes

std::unique_ptr< dynamic_reconfigure::Server< SilhouetteMatchConfig > > dyn_reconf_
 
ros::NodeHandle nh_
 
std::unique_ptr< rc_rest_api::RestHelperrest_helper_
 
std::vector< ros::ServiceServersrvs_
 
std::unique_ptr< Visualizervisualizer_
 

Detailed Description

Definition at line 55 of file rc_silhouettematch_client.h.

Constructor & Destructor Documentation

rc_silhouettematch_client::SilhouetteMatchClient::SilhouetteMatchClient ( const std::string &  host,
ros::NodeHandle nh 
)

Definition at line 41 of file rc_silhouettematch_client.cpp.

rc_silhouettematch_client::SilhouetteMatchClient::~SilhouetteMatchClient ( )
default

Member Function Documentation

bool rc_silhouettematch_client::SilhouetteMatchClient::calibrateBasePlane ( CalibrateBasePlane::Request &  req,
CalibrateBasePlane::Response &  res 
)
protected

Definition at line 96 of file rc_silhouettematch_client.cpp.

template<typename Request , typename Response >
bool rc_silhouettematch_client::SilhouetteMatchClient::callService ( const std::string &  name,
const Request &  req,
Response &  res 
)
protected

Definition at line 61 of file rc_silhouettematch_client.cpp.

bool rc_silhouettematch_client::SilhouetteMatchClient::deleteBasePlaneCalib ( DeleteBasePlaneCalibration::Request &  req,
DeleteBasePlaneCalibration::Response &  res 
)
protected

Definition at line 113 of file rc_silhouettematch_client.cpp.

bool rc_silhouettematch_client::SilhouetteMatchClient::deleteROIs ( DeleteRegionsOfInterest::Request &  req,
DeleteRegionsOfInterest::Response &  res 
)
protected

Definition at line 132 of file rc_silhouettematch_client.cpp.

bool rc_silhouettematch_client::SilhouetteMatchClient::detectObject ( DetectObject::Request &  req,
DetectObject::Response &  res 
)
protected

Definition at line 86 of file rc_silhouettematch_client.cpp.

bool rc_silhouettematch_client::SilhouetteMatchClient::getBasePlaneCalib ( GetBasePlaneCalibration::Request &  req,
GetBasePlaneCalibration::Response &  res 
)
protected

Definition at line 106 of file rc_silhouettematch_client.cpp.

bool rc_silhouettematch_client::SilhouetteMatchClient::getROIs ( GetRegionsOfInterest::Request &  req,
GetRegionsOfInterest::Response &  res 
)
protected

Definition at line 126 of file rc_silhouettematch_client.cpp.

void rc_silhouettematch_client::SilhouetteMatchClient::initParameters ( )
protected

Definition at line 156 of file rc_silhouettematch_client.cpp.

bool rc_silhouettematch_client::SilhouetteMatchClient::setROI ( SetRegionOfInterest::Request &  req,
SetRegionOfInterest::Response &  res 
)
protected

Definition at line 120 of file rc_silhouettematch_client.cpp.

void rc_silhouettematch_client::SilhouetteMatchClient::updateParameters ( SilhouetteMatchConfig &  config,
uint32_t   
)
protected

Definition at line 185 of file rc_silhouettematch_client.cpp.

Member Data Documentation

std::unique_ptr<dynamic_reconfigure::Server<SilhouetteMatchConfig> > rc_silhouettematch_client::SilhouetteMatchClient::dyn_reconf_
private

Definition at line 89 of file rc_silhouettematch_client.h.

ros::NodeHandle rc_silhouettematch_client::SilhouetteMatchClient::nh_
private

Definition at line 85 of file rc_silhouettematch_client.h.

std::unique_ptr<rc_rest_api::RestHelper> rc_silhouettematch_client::SilhouetteMatchClient::rest_helper_
private

Definition at line 88 of file rc_silhouettematch_client.h.

std::vector<ros::ServiceServer> rc_silhouettematch_client::SilhouetteMatchClient::srvs_
private

Definition at line 86 of file rc_silhouettematch_client.h.

std::unique_ptr<Visualizer> rc_silhouettematch_client::SilhouetteMatchClient::visualizer_
private

Definition at line 90 of file rc_silhouettematch_client.h.


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


rc_silhouettematch_client
Author(s): Elena Gambaro
autogenerated on Sat Feb 13 2021 03:42:03