Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041 #include <ros/ros.h>
00042 #include <opencv2/core/core.hpp>
00043 #include <image_transport/image_transport.h>
00044 #include <cv_bridge/cv_bridge.h>
00045 #include <sensor_msgs/image_encodings.h>
00046 #include <dynamic_reconfigure/server.h>
00047 #include <blort_ros/DetectorConfig.h>
00048 #include <blort_ros/SetCameraInfo.h>
00049 #include "../gldetector.h"
00050
00051 class DetectorNode
00052 {
00053 private:
00054 ros::NodeHandle nh_;
00055 image_transport::ImageTransport it_;
00056 image_transport::Publisher image_pub;
00057 ros::Subscriber cam_info_sub;
00058 const std::string root_;
00059 ros::ServiceServer pose_service;
00060 ros::ServiceServer cam_info_service;
00061 std::auto_ptr<dynamic_reconfigure::Server<blort_ros::DetectorConfig> > server_;
00062 dynamic_reconfigure::Server<blort_ros::DetectorConfig>::CallbackType f_;
00063 blort_ros::GLDetector* detector;
00064 unsigned int counter;
00065
00066 double nn_match_threshold;
00067 int ransac_n_points_to_match;
00068
00069
00070
00071
00072 public:
00073 DetectorNode(std::string root = ".")
00074 : nh_("blort_detector"), it_(nh_), root_(root), detector(0)
00075 {
00076 cam_info_sub = nh_.subscribe("/blort_camera_info", 1, &DetectorNode::cam_info_callback, this);
00077 image_pub = it_.advertise("image_result", 1);
00078
00079 cam_info_service = nh_.advertiseService("set_camera_info", &DetectorNode::setCameraInfoCb, this);
00080 counter = 0;
00081
00082 nh_.param<double>("nn_match_threshold", nn_match_threshold, 0.65);
00083 nh_.param<int>("ransac_n_points_to_match", ransac_n_points_to_match, 4);
00084
00085 }
00086
00087 ~DetectorNode()
00088 {
00089 if(detector != 0)
00090 delete(detector);
00091 }
00092
00093 bool recovery(blort_ros::RecoveryCall::Request &req,
00094 blort_ros::RecoveryCall::Response &resp)
00095 {
00096 if(detector != 0)
00097 {
00098 ROS_INFO("Detector called the %u-th time.", ++counter);
00099 bool result;
00100 if(!req.Image.data.empty())
00101 {
00102 cv_bridge::CvImagePtr cv_ptr;
00103 try
00104 {
00105
00106 cv_ptr = cv_bridge::toCvCopy(req.Image, req.Image.encoding);
00107 ROS_INFO_STREAM("\n\nENCODING = " << req.Image.encoding << "\n\n\n");
00108 }
00109 catch (cv_bridge::Exception& e)
00110 {
00111 ROS_ERROR("cv_bridge exception: %s", e.what());
00112 return false;
00113 }
00114 result = detector->recovery(cv_ptr->image, resp);
00115 } else {
00116 ROS_INFO("Running detector on latest image.");
00117 result = detector->recoveryWithLast(resp);
00118 }
00119 cv_bridge::CvImage out_msg;
00120 out_msg.header = req.Image.header;
00121 out_msg.header.stamp = ros::Time::now();
00122
00123 out_msg.encoding = sensor_msgs::image_encodings::BGR8;
00124 out_msg.image = detector->getImage();
00125 image_pub.publish(out_msg.toImageMsg());
00126
00127
00128
00129
00130
00131
00132
00133
00134 ROS_INFO("\n");
00135 ROS_INFO_STREAM("= > detector_node returned " << result << "\n");
00136 ROS_INFO("\n");
00137
00138 return result;
00139 } else {
00140 ROS_ERROR("blort_detector service called while the core is uninitialized.");
00141 return false;
00142 }
00143 }
00144
00145 bool setCameraInfoCb(blort_ros::SetCameraInfo::Request &req,
00146 blort_ros::SetCameraInfo::Response &resp)
00147 {
00148 if(detector == 0)
00149 cam_info_callback(req.CameraInfo);
00150 return true;
00151 }
00152
00153 void reconf_callback(blort_ros::DetectorConfig &config, uint32_t level)
00154 {
00155 if(detector != 0)
00156 {
00157 detector->reconfigure(config);
00158 ROS_INFO("Detector confidence threshold set to %f", config.recovery_conf_threshold);
00159 } else {
00160 ROS_WARN("Please publish camera_info for the tracker initialization.");
00161 }
00162 }
00163
00164 void cam_info_callback(const sensor_msgs::CameraInfo &msg)
00165 {
00166 if(detector == 0)
00167 {
00168 ROS_INFO("Camera parameters received, ready to run.");
00169 cam_info_sub.shutdown();
00170 detector = new blort_ros::GLDetector(msg, root_);
00171 if(nn_match_threshold != 0.0)
00172 detector->setNNThreshold(nn_match_threshold);
00173 if(ransac_n_points_to_match != 0)
00174 detector->setRansacNPointsToMatch(ransac_n_points_to_match);
00175 pose_service = nh_.advertiseService("pose_service", &DetectorNode::recovery, this);
00176
00177 server_ = std::auto_ptr<dynamic_reconfigure::Server<blort_ros::DetectorConfig> >
00178 (new dynamic_reconfigure::Server<blort_ros::DetectorConfig>());
00179 f_ = boost::bind(&DetectorNode::reconf_callback, this, _1, _2);
00180 server_->setCallback(f_);
00181 }
00182 }
00183 };
00184
00185 int main(int argc, char *argv[] )
00186 {
00187 if(argc < 2)
00188 {
00189 ROS_ERROR("The first command line argument should be the package root!");
00190 return -1;
00191 }
00192 ros::init(argc, argv, "blort_detector");
00193 DetectorNode node(argv[1]);
00194 ros::spin();
00195 return 0;
00196 }
00197