rc_silhouettematch_client.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2020 Roboception GmbH
3  *
4  * Author: Elena Gambaro
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright notice,
10  * this list of conditions and the following disclaimer.
11  *
12  * 2. Redistributions in binary form must reproduce the above copyright notice,
13  * this list of conditions and the following disclaimer in the documentation
14  * and/or other materials provided with the distribution.
15  *
16  * 3. Neither the name of the copyright holder nor the names of its contributors
17  * may be used to endorse or promote products derived from this software without
18  * specific prior written permission.
19  *
20  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
21  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
22  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
23  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
24  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
25  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
26  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
27  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
28  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
29  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  */
32 
33 #ifndef RC_SILHOUETTEMATCH_CLIENT_H
34 #define RC_SILHOUETTEMATCH_CLIENT_H
35 
36 #include <ros/ros.h>
37 
38 #include <rc_silhouettematch_client/DetectObject.h>
39 #include <rc_silhouettematch_client/CalibrateBasePlane.h>
40 #include <rc_silhouettematch_client/DeleteBasePlaneCalibration.h>
41 #include <rc_silhouettematch_client/GetBasePlaneCalibration.h>
42 #include <rc_silhouettematch_client/SetRegionOfInterest.h>
43 #include <rc_silhouettematch_client/GetRegionsOfInterest.h>
44 #include <rc_silhouettematch_client/DeleteRegionsOfInterest.h>
45 
46 #include <dynamic_reconfigure/server.h>
47 #include <rc_silhouettematch_client/SilhouetteMatchConfig.h>
48 
49 #include "rest_helper.h"
50 
52 {
53 class Visualizer;
54 
56 {
57 public:
58  SilhouetteMatchClient(const std::string& host, ros::NodeHandle& nh);
59 
61 
62 protected:
63  bool detectObject(DetectObject::Request& req, DetectObject::Response& res);
64 
65  bool calibrateBasePlane(CalibrateBasePlane::Request& req, CalibrateBasePlane::Response& res);
66 
67  bool getBasePlaneCalib(GetBasePlaneCalibration::Request& req, GetBasePlaneCalibration::Response& res);
68 
69  bool deleteBasePlaneCalib(DeleteBasePlaneCalibration::Request& req, DeleteBasePlaneCalibration::Response& res);
70 
71  bool setROI(SetRegionOfInterest::Request& req, SetRegionOfInterest::Response& res);
72 
73  bool getROIs(GetRegionsOfInterest::Request& req, GetRegionsOfInterest::Response& res);
74 
75  bool deleteROIs(DeleteRegionsOfInterest::Request& req, DeleteRegionsOfInterest::Response& res);
76 
77  void initParameters();
78 
79  void updateParameters(SilhouetteMatchConfig& config, uint32_t);
80 
81  template <typename Request, typename Response>
82  bool callService(const std::string& name, const Request& req, Response& res);
83 
84 private:
86  std::vector<ros::ServiceServer> srvs_;
87 
88  std::unique_ptr<rc_rest_api::RestHelper> rest_helper_;
89  std::unique_ptr<dynamic_reconfigure::Server<SilhouetteMatchConfig>> dyn_reconf_;
90  std::unique_ptr<Visualizer> visualizer_;
91 };
92 
93 } // namespace rc_silhouettematch_client
94 
95 #endif // RC_SILHOUETTEMATCH_CLIENT_H
void updateParameters(SilhouetteMatchConfig &config, uint32_t)
bool getROIs(GetRegionsOfInterest::Request &req, GetRegionsOfInterest::Response &res)
bool detectObject(DetectObject::Request &req, DetectObject::Response &res)
bool callService(const std::string &name, const Request &req, Response &res)
SilhouetteMatchClient(const std::string &host, ros::NodeHandle &nh)
std::unique_ptr< rc_rest_api::RestHelper > rest_helper_
std::unique_ptr< dynamic_reconfigure::Server< SilhouetteMatchConfig > > dyn_reconf_
bool deleteROIs(DeleteRegionsOfInterest::Request &req, DeleteRegionsOfInterest::Response &res)
bool deleteBasePlaneCalib(DeleteBasePlaneCalibration::Request &req, DeleteBasePlaneCalibration::Response &res)
bool getBasePlaneCalib(GetBasePlaneCalibration::Request &req, GetBasePlaneCalibration::Response &res)
bool setROI(SetRegionOfInterest::Request &req, SetRegionOfInterest::Response &res)
bool calibrateBasePlane(CalibrateBasePlane::Request &req, CalibrateBasePlane::Response &res)


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