1 #include <gtest/gtest.h> 5 #include <opencv2/highgui/highgui.hpp> 8 #include "dnn_detect/DetectedObject.h" 9 #include "dnn_detect/DetectedObjectArray.h" 10 #include "dnn_detect/Detect.h" 12 #include <boost/thread/thread.hpp> 14 #if CV_MAJOR_VERSION < 4 15 #define IMREAD_COLOR_MODE CV_LOAD_IMAGE_COLOR 17 #define IMREAD_COLOR_MODE cv::IMREAD_COLOR 70 for (
const auto& obj : results.objects) {
71 if (obj.class_name ==
"cat") {
90 int main(
int argc,
char** argv)
93 testing::InitGoogleTest(&argc, argv);
95 return RUN_ALL_TESTS();
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
void publish_image(std::string file)
std::string image_directory
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
image_transport::Publisher image_pub
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
bool call(MReq &req, MRes &res)
void object_callback(const dnn_detect::DetectedObjectArray &results)
int main(int argc, char **argv)
ros::Subscriber object_sub
void publish(const sensor_msgs::Image &message) const
#define IMREAD_COLOR_MODE
image_transport::ImageTransport * it
TEST_F(DnnImagesTest, cat)
bool getParam(const std::string &key, std::string &s) const
ROSCPP_DECL void spinOnce()
sensor_msgs::ImagePtr toImageMsg() const