find_objects.cpp
Go to the documentation of this file.
1 
2 
3 
4 #include <ros/ros.h>
5 #include <std_msgs/String.h>
6 #include <std_msgs/Bool.h>
8 #include <opencv2/opencv.hpp>
9 #include <cv_bridge/cv_bridge.h>
10 #include <geometry_msgs/PointStamped.h>
11 
13 #include <tf/transform_listener.h>
14 #include <robotican_common/FindObjectDynParamConfig.h>
15 #include <dynamic_reconfigure/server.h>
16 
18 #include "tf/message_filter.h"
20 #include <ar_track_alvar_msgs/AlvarMarkers.h>
21 #include <robotican_msgs_srvs/switch_topic.h>
22 
23 using namespace cv;
24 using namespace std;
25 bool debug_vision=false;
26 
27 
28 bool find_object(Mat input, pcl::PointCloud<pcl::PointXYZRGBA>::Ptr cloud,Point3d *obj,std::string frame);
29 void cloud_cb(const sensor_msgs::PointCloud2ConstPtr& input);
30 void dynamicParamCallback(robotican_common::FindObjectDynParamConfig &config, uint32_t level);
32 
33 
34 
35 
37 
38 //bool timeout=true;
39 
41 
42 //ros::Time detect_t;
43 
45 bool have_object=false;
46 
52 //red
53 int minH=3,maxH=160;
54 int minS=70,maxS=255;
55 
56 int minV=10,maxV=255;
57 int minA=200,maxA=50000;
60 int morph_size=0;
61 
62 int inv_H=1;
63 
64 
65 
66 
67 void cloud_cb(const sensor_msgs::PointCloud2ConstPtr& input) {
68 
69  //pcl - point clound library with lot of algorithms
70 
71  pcl::PointCloud<pcl::PointXYZRGBA> cloud;
72  //convert ros point cloud msg to pcl point cloud
73  pcl::fromROSMsg (*input, cloud);
74  //create projection image from p.c.
75  pcl::PointCloud<pcl::PointXYZRGBA>::Ptr cloudp (new pcl::PointCloud<pcl::PointXYZRGBA> (cloud));
76 
77  if (cloudp->empty()) {
78 
79  ROS_WARN("empty cloud");
80  return;
81  }
82  //creating new ros sensor msg - picture is relative to depth camera tf
83  sensor_msgs::ImagePtr image_msg(new sensor_msgs::Image);
84  pcl::toROSMsg (*input, *image_msg);
85  image_msg->header.stamp = input->header.stamp;
86  image_msg->header.frame_id = input->header.frame_id;
87 
88 
90  Mat result=cv_ptr->image;
91 
92  Point3d obj;
93  //find object
94  have_object= find_object(result,cloudp,&obj,input->header.frame_id);
95 
96  waitKey(1);
97 
98 
99 
100  if (have_object) {
101 
102  //publish geometry msg containing object's location
103  geometry_msgs::PoseStamped target_pose;
104  target_pose.header.frame_id=input->header.frame_id;
105  target_pose.header.stamp=ros::Time::now();
106  target_pose.pose.position.x =obj.x;
107  target_pose.pose.position.y = obj.y;
108  target_pose.pose.position.z = obj.z;
109  target_pose.pose.orientation.w=1;
110  pose_pub.publish(target_pose);
111 
112  }
113 
114 
115 }
116 
118 {
119  //get object location msg
120  try
121  {
122  geometry_msgs::PoseStamped base_object_pose;
123  listener_ptr->transformPose("base_footprint", *point_ptr, base_object_pose);
124  base_object_pose.pose.orientation= tf::createQuaternionMsgFromRollPitchYaw(0.0,0.0,0.0);
125 
126  //simulate alvar msgs, to get tf
127  ar_track_alvar_msgs::AlvarMarkers msg;
128  msg.header.stamp=base_object_pose.header.stamp;
129  msg.header.frame_id="base_footprint";
130 
131  ar_track_alvar_msgs::AlvarMarker m;
132  m.id=object_id;
133  m.header.stamp=base_object_pose.header.stamp;
134  m.header.frame_id="base_footprint";
135  m.pose=base_object_pose;
136  msg.markers.push_back(m);
137 
138  m.pose.pose.position.z-=0.1;
139  m.id=2;
140  msg.markers.push_back(m);
141 
142  object_pub.publish(msg);
143 
144 
145  }
146  catch (tf::TransformException &ex)
147  {
148  printf ("Failure %s\n", ex.what()); //Print exception which was caught
149  }
150 }
151 
152 bool find_object(Mat input, pcl::PointCloud<pcl::PointXYZRGBA>::Ptr cloudp,Point3d *pr,std::string frame) {
153 
154  Mat hsv,filtered,bw,mask;
155 
156  cv_bridge::CvImage out_msg;
157  out_msg.header.stamp=ros::Time::now();
158  out_msg.header.frame_id= frame;
159  //use hsv colores - no light sensitivity
160  cvtColor(input,hsv,CV_BGR2HSV);
161 
162 
163  if (inv_H) {
164  //edges of spectrom - red colore
165  Mat lower_hue_range;
166  Mat upper_hue_range;
167  inRange(hsv, cv::Scalar(0, minS, minV), cv::Scalar(minH, maxS, maxV), lower_hue_range);
168  inRange(hsv, cv::Scalar(maxH, minS, minV), cv::Scalar(179, maxS, maxV), upper_hue_range);
169  // Combine the above two images
170 
171  addWeighted(lower_hue_range, 1.0, upper_hue_range, 1.0, 0.0, mask);
172  }
173  else{
174  //if not red use (middle of spectrom):
175  inRange(hsv,Scalar(minH,minS,minV),Scalar(maxH,maxS,maxV),mask);
176  }
177  hsv.copyTo(filtered,mask);
178  cvtColor(filtered,filtered,CV_HSV2BGR);
179 
180  out_msg.image = filtered;
181  out_msg.encoding = "bgr8";
182  object_image_pub.publish(out_msg.toImageMsg());
183  //convert to bw image, gaussian - blur, morphologic actions
184  mask.copyTo(bw);
185  if (gaussian_ksize>0) {
186  if (gaussian_ksize % 2 == 0) gaussian_ksize++;
187  GaussianBlur( bw, bw, Size(gaussian_ksize,gaussian_ksize), gaussian_sigma , 0);
188  }
189 
190 
191  if (morph_size>0) {
192  Mat element = getStructuringElement( MORPH_ELLIPSE, Size( 2*morph_size + 1, 2*morph_size+1 ), Point( morph_size, morph_size ) );
193  morphologyEx( bw, bw, MORPH_CLOSE, element, Point(-1,-1), 1 );
194  }
195 
196  out_msg.image = bw;
198  bw_image_pub.publish(out_msg.toImageMsg());
199 
200  //get image contours
201  vector<vector<Point>> contours;
202  vector<Vec4i> hierarchy;
203 
204  findContours(bw, contours,hierarchy,CV_RETR_CCOMP, CV_CHAIN_APPROX_SIMPLE);
205 
206  //get largest contour
207  double largest_area=0;
208  int largest_contour_index=0;
209  for( int i = 0; i< contours.size(); i++ )
210  {
211  double area0 = abs(contourArea(contours[i]));
212  if(area0>largest_area){
213  largest_area=area0;
214  largest_contour_index=i;
215  }
216  }
217  bool ok=false;
218  if ((largest_area>minA)&&(largest_area<maxA)) {
219 
220  //draw contours and details about object
221  drawContours(input, contours, (int)largest_contour_index, Scalar(255,0,0), 3, 8, hierarchy, 0);
222  Moments mu=moments( contours[largest_contour_index], true );
223  Point2f mc = Point2f( mu.m10/mu.m00 , mu.m01/mu.m00 );
224  circle( input, mc, 4, Scalar(0,0,255), -1, 8, 0 );
225  int pcl_index = ((int)(mc.y)*input.cols) + (int)(mc.x);
226  circle( input, mc, 8, Scalar(0,255,0), -1, 8, 0 );
227 
228  pr->x=cloudp->points[pcl_index].x;
229  pr->y=cloudp->points[pcl_index].y;
230  pr->z=cloudp->points[pcl_index].z;
231  char str[100];
232  if (isnan (pr->x) || isnan (pr->y) || isnan (pr->z) ) {
233  sprintf(str,"NaN");
234  ok=false;
235  }
236  else {
237  sprintf(str,"[%.3f,%.3f,%.3f] A=%lf",pr->x,pr->y,pr->z,largest_area);
238  ok=true;
239  }
240  putText( input, str, mc, CV_FONT_HERSHEY_COMPLEX, 0.4, Scalar(255,255,255), 1, 8);
241 
242  }
243 
244 
245  out_msg.image = input;
246  out_msg.encoding = "bgr8";
247  result_image_pub.publish(out_msg.toImageMsg());
248 
249  return ok;
250 }
251 
252 void dynamicParamCallback(robotican_common::FindObjectDynParamConfig &config, uint32_t level) {
253  minH = config.H_min;
254  maxH = config.H_max;
255 
256  minS = config.S_min;
257  maxS = config.S_max;
258 
259  minV = config.V_min;
260  maxV = config.V_max;
261 
262  minA = config.A_min;
263  maxA = config.A_max;
264 
265  gaussian_ksize = config.gaussian_ksize;
266  gaussian_sigma = config.gaussian_sigma;
267 
268  morph_size = config.morph_size;
269 
270  inv_H = config.invert_Hue;
271 }
272 
273 
274 void on_trackbar( int, void* ){}
275 
276 bool switch_pcl_topic(robotican_msgs_srvs::switch_topic::Request &req, robotican_msgs_srvs::switch_topic::Response &res) {
277 
278  if (req.num==1) depth_topic=depth_topic1;
279  else if (req.num==2) depth_topic=depth_topic2;
280  res.success=true;
281 return true;
282 }
283 
284 int main(int argc, char **argv) {
285 
286  ros::init(argc, argv, "find_objects_node");
287  ros::NodeHandle n;
288  ros::NodeHandle pn("~");
289 
290  pn.param<int>("object_id", object_id, 1);
291  pn.param<std::string>("depth_topic1", depth_topic1, "/kinect2/qhd/points");
292  pn.param<std::string>("depth_topic2", depth_topic2, "/kinect2/qhd/points");
294 
295  dynamic_reconfigure::Server<robotican_common::FindObjectDynParamConfig> dynamicServer;
296  dynamic_reconfigure::Server<robotican_common::FindObjectDynParamConfig>::CallbackType callbackFunction;
297 
298  callbackFunction = boost::bind(&dynamicParamCallback, _1, _2);
299  dynamicServer.setCallback(callbackFunction);
300 
302 
303  result_image_pub = it_.advertise("result", 1);
304  object_image_pub = it_.advertise("hsv_filterd", 1);
305  bw_image_pub = it_.advertise("bw", 1);
306  ros::Subscriber pcl_sub = n.subscribe(depth_topic, 1, cloud_cb);
307  ROS_INFO_STREAM(depth_topic);
308 
309  object_pub=n.advertise<ar_track_alvar_msgs::AlvarMarkers>("detected_objects", 2, true);
310 
311  pose_pub=pn.advertise<geometry_msgs::PoseStamped>("object_pose",10);
312 
313  //convert depth cam tf to base foot print tf (moveit work with base foot print tf)
314  tf::TransformListener listener;
315  listener_ptr=&listener;
316 
318  point_sub_.subscribe(pn, "object_pose", 10);
319 
320  tf::MessageFilter<geometry_msgs::PoseStamped> tf_filter(point_sub_, listener, "base_footprint", 10);
321  tf_filter.registerCallback( boost::bind(obj_msgCallback, _1) );
322 
323 
324 ros::ServiceServer switch_sub = n.advertiseService("switch_pcl_topic", &switch_pcl_topic);
325 
326 ros::Rate r(10);
327  ROS_INFO("Ready to find objects!");
328  while (ros::ok()) {
329  if (pcl_sub.getTopic()!=depth_topic) {
330  pcl_sub = n.subscribe(depth_topic, 1, cloud_cb);
331  ROS_INFO("switching pcl topic");
332  }
333  ros::spinOnce();
334  r.sleep();
335  }
336 
337  return 0;
338 }
339 
void on_trackbar(int, void *)
int maxV
tf::TransformListener * listener_ptr
int gaussian_sigma
int minA
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
int maxS
bool find_object(Mat input, pcl::PointCloud< pcl::PointXYZRGBA >::Ptr cloud, Point3d *obj, std::string frame)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::string encoding
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
bool switch_pcl_topic(robotican_msgs_srvs::switch_topic::Request &req, robotican_msgs_srvs::switch_topic::Response &res)
void arm_msgCallback(const boost::shared_ptr< const geometry_msgs::PoseStamped > &point_ptr)
const std::string TYPE_8UC1
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
ros::Publisher pose_pub
void cloud_cb(const sensor_msgs::PointCloud2ConstPtr &input)
bool have_object
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
#define ROS_WARN(...)
int minS
void dynamicParamCallback(robotican_common::FindObjectDynParamConfig &config, uint32_t level)
int morph_size
std::string depth_topic
int minV
CvImagePtr cvtColor(const CvImageConstPtr &source, const std::string &encoding)
void publish(const sensor_msgs::Image &message) const
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
std::string getTopic() const
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
ROSCPP_DECL bool ok()
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
int maxA
bool sleep()
int inv_H
image_transport::Publisher bw_image_pub
image_transport::Publisher result_image_pub
int minH
#define ROS_INFO_STREAM(args)
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
int maxH
void transformPose(const std::string &target_frame, const geometry_msgs::PoseStamped &stamped_in, geometry_msgs::PoseStamped &stamped_out) const
std::string depth_topic1
static geometry_msgs::Quaternion createQuaternionMsgFromRollPitchYaw(double roll, double pitch, double yaw)
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
static Time now()
void obj_msgCallback(const boost::shared_ptr< const geometry_msgs::PoseStamped > &point_ptr)
ros::Publisher object_pub
ROSCPP_DECL void spinOnce()
r
std::string depth_topic2
int gaussian_ksize
int object_id
bool debug_vision
sensor_msgs::ImagePtr toImageMsg() const
std_msgs::Header header
int main(int argc, char **argv)
image_transport::Publisher object_image_pub
Connection registerCallback(const C &callback)


robotican_common
Author(s):
autogenerated on Wed Jan 3 2018 03:48:33