block_manipulation.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2011, Vanadium Labs LLC
3  * All Rights Reserved
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of Vanadium Labs LLC nor the names of its
14  * contributors may be used to endorse or promote products derived
15  * from this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
18  * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
19  * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
20  * DISCLAIMED. IN NO EVENT SHALL VANADIUM LABS BE LIABLE FOR ANY DIRECT, INDIRECT,
21  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
22  * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
23  * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
24  * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
25  * OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
26  * ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27  *
28  * Author: Michael Ferguson, Helen Oleynikova
29  */
30 
31 
32 #include <ros/ros.h>
33 #include <sensor_msgs/PointCloud2.h>
34 
36 #include <simple_arm_server/MoveArmAction.h>
37 
38 #include <pcl/conversions.h>
39 #include <pcl/point_cloud.h>
40 #include <pcl/point_types.h>
41 #include <pcl/filters/passthrough.h>
42 #include <pcl/segmentation/extract_clusters.h>
43 #include <pcl/kdtree/kdtree.h>
44 
45 #include <pcl_ros/point_cloud.h>
46 #include <pcl_ros/transforms.h>
47 
49 
50 #include <vector>
51 
52 
53 using namespace visualization_msgs;
54 
55 const std::string arm_link = "/arm_base_link";
56 const double gripper_open = 0.04;
57 const double gripper_closed = 0.024;
58 
59 const double z_up = 0.08;
60 const double z_down = -0.04;
61 
62 const double block_size = 0.0127;
63 
64 // Block storage
65 class Block
66 {
67  public:
68  int id;
69  bool active;
70  double x;
71  double y;
72 
73  Block(const Block& b) : id(b.id), active(b.active), x(b.x), y(b.y) {}
74  Block(int _id, double _x, double _y) : id(_id) , active(true), x(_x), y(_y) {}
75 
76  std::string getName()
77  {
78  std::stringstream conv;
79  conv << id;
80  return std::string("block") + conv.str();
81  }
82 };
83 
84 
86 {
87 private:
93  int markers_;
94  int moving_;
95  int skip_;
96  float x_, y_;
97  std::string last_block_;
98  std::vector<Block> marker_names_;
99 
101 
102 public:
103 
104  BlockManipulation() : server("block_controls"), client_("move_arm", true)
105  {
106  // create marker server
107  markers_ = 0;
108  last_block_ = std::string("");
109 
110  ros::Duration(0.1).sleep();
111 
112  skip_ = 0;
113 
114  // open gripper
115  simple_arm_server::MoveArmGoal goal;
116  simple_arm_server::ArmAction grip;
117  grip.type = simple_arm_server::ArmAction::MOVE_GRIPPER;
118  grip.command = gripper_open;
119  goal.motions.push_back(grip);
120  goal.header.frame_id = arm_link;
121  client_.sendGoal(goal);
122  client_.waitForResult(/*ros::Duration(30.0)*/);
123 
124  // subscribe to point cloud
125  sub_ = nh.subscribe("/camera/depth_registered/points", 1, &BlockManipulation::cloudCb, this);
126  pub_ = nh.advertise< pcl::PointCloud<pcl::PointXYZRGB> >("block_output", 1);
127 
128  server.applyChanges();
129 
130  ROS_INFO("Finished initializing.");
131  }
132 
133  // Move the real block!
134  void moveBlock( const InteractiveMarkerFeedbackConstPtr &feedback )
135  {
136  switch ( feedback->event_type )
137  {
138  case visualization_msgs::InteractiveMarkerFeedback::MOUSE_DOWN:
139  ROS_INFO_STREAM("Staging " << feedback->marker_name);
140  x_ = feedback->pose.position.x;
141  y_ = feedback->pose.position.y;
142  last_block_ = feedback->marker_name;
143  break;
144 
145  case visualization_msgs::InteractiveMarkerFeedback::MOUSE_UP:
146  moving_ = true;
147  ROS_INFO_STREAM("Now moving " << feedback->marker_name);
148 
149  simple_arm_server::MoveArmGoal goal;
150  simple_arm_server::ArmAction action;
151 
152  /* arm straight up */
153  tf::Quaternion temp;
154  temp.setRPY(0,1.57,0);
155  action.goal.orientation.x = temp.getX();
156  action.goal.orientation.y = temp.getY();
157  action.goal.orientation.z = temp.getZ();
158  action.goal.orientation.w = temp.getW();
159 
160  /* hover over */
161  action.goal.position.x = x_;
162  action.goal.position.y = y_;
163  action.goal.position.z = z_up;
164  goal.motions.push_back(action);
165  action.move_time.sec = 1.5;
166 
167  /* go down */
168  action.goal.position.z = z_down;
169  goal.motions.push_back(action);
170  action.move_time.sec = 1.5;
171 
172  /* close gripper */
173  simple_arm_server::ArmAction grip;
174  grip.type = simple_arm_server::ArmAction::MOVE_GRIPPER;
175  grip.command = gripper_closed;
176  grip.move_time.sec = 1.0;
177  goal.motions.push_back(grip);
178 
179  /* go up */
180  action.goal.position.z = z_up;
181  goal.motions.push_back(action);
182  action.move_time.sec = 0.25;
183 
184  /* hover over */
185  action.goal.position.x = feedback->pose.position.x;
186  action.goal.position.y = feedback->pose.position.y;
187  action.goal.position.z = z_up;
188  goal.motions.push_back(action);
189  action.move_time.sec = 1.5;
190 
191  /* go down */
192  action.goal.position.z = z_down;
193  goal.motions.push_back(action);
194  action.move_time.sec = 1.5;
195 
196  /* open gripper */
197  grip.command = gripper_open;
198  goal.motions.push_back(grip);
199 
200  /* go up */
201  action.goal.position.z = z_up;
202  goal.motions.push_back(action);
203  action.move_time.sec = 0.25;
204 
205  goal.header.frame_id = arm_link;
206  client_.sendGoal(goal);
207  client_.waitForResult(/*ros::Duration(30.0)*/);
208  /* update location */
209  for( std::vector<Block>::iterator it=marker_names_.begin(); it < marker_names_.end(); it++)
210  {
211  if( it->getName() == feedback->marker_name )
212  {
213  it->x = feedback->pose.position.x;
214  it->y = feedback->pose.position.y;
215  break;
216  }
217  }
218 
219  moving_ = false;
220  break;
221  }
222 
223  server.applyChanges();
224  }
225 
226  // Make a box
227  Marker makeBox( InteractiveMarker &msg, float r, float g, float b )
228  {
229  Marker m;
230 
231  m.type = Marker::CUBE;
232  m.scale.x = msg.scale;
233  m.scale.y = msg.scale;
234  m.scale.z = msg.scale;
235  m.color.r = r;
236  m.color.g = g;
237  m.color.b = b;
238  m.color.a = 1.0;
239 
240  return m;
241  }
242 
243  // Add a new block
244  void addBlock( float x, float y, float z, float rz, float r, float g, float b, int n)
245  {
246  InteractiveMarker marker;
247  marker.header.frame_id = arm_link;
248  marker.pose.position.x = x;
249  marker.pose.position.y = y;
250  marker.pose.position.z = z;
251  marker.scale = 0.03;
252 
253  Block block( n, x, y );
254  marker_names_.push_back( block );
255  marker.name = block.getName();
256  marker.description = "Another block";
257 
258  InteractiveMarkerControl control;
259  control.orientation.w = 1;
260  control.orientation.x = 0;
261  control.orientation.y = 1;
262  control.orientation.z = 0;
263  control.interaction_mode = InteractiveMarkerControl::MOVE_PLANE;
264  marker.controls.push_back( control );
265 
266  control.markers.push_back( makeBox(marker, r, g, b) );
267  control.always_visible = true;
268  marker.controls.push_back( control );
269 
270 
271  server.insert( marker );
272  server.setCallback( marker.name, boost::bind( &BlockManipulation::moveBlock, this, _1 ));
273  }
274 
275  // Process an incoming cloud
276  void cloudCb ( const sensor_msgs::PointCloud2ConstPtr& msg )
277  {
278  if( (skip_++)%15 != 0 ) return;
279 
280  // convert to PCL
281  pcl::PointCloud<pcl::PointXYZRGB> cloud;
282  pcl::fromROSMsg (*msg, cloud);
283 
284  // transform to base_link
285  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_transformed (new pcl::PointCloud<pcl::PointXYZRGB>);
286 
287  tf_listener_.waitForTransform(std::string(arm_link), cloud.header.frame_id, cloud.header.stamp, ros::Duration(1.0));
288  if (!pcl_ros::transformPointCloud (std::string(arm_link), cloud, *cloud_transformed, tf_listener_))
289  {
290  ROS_ERROR ("Error converting to base_link");
291  return;
292  }
293 
294  // drop things on ground
295  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_filtered (new pcl::PointCloud<pcl::PointXYZRGB>);
296  pcl::PassThrough<pcl::PointXYZRGB> pass;
297  pass.setInputCloud(cloud_transformed);
298  pass.setFilterFieldName("z");
299  pass.setFilterLimits(z_down - 0.01, z_down + block_size*2);
300  pass.filter(*cloud_filtered);
301  if( cloud_filtered->points.size() == 0 ){
302  ROS_ERROR("0 points left");
303  return;
304  }else
305  ROS_INFO("Filtered, %d points left", (int) cloud_filtered->points.size());
306  pub_.publish(*cloud_filtered);
307 
308  // cluster
309  pcl::search::KdTree<pcl::PointXYZRGB>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZRGB>);
310  tree->setInputCloud(cloud_filtered);
311 
312  std::vector<pcl::PointIndices> clusters;
313  pcl::EuclideanClusterExtraction<pcl::PointXYZRGB> ec;
314  ec.setClusterTolerance(0.02);
315  ec.setMinClusterSize(20);
316  ec.setMaxClusterSize(25000);
317  ec.setSearchMethod(tree);
318  ec.setInputCloud(cloud_filtered);
319  ec.extract(clusters);
320 
321  // need to delete old blocks
322  for( std::vector<Block>::iterator it=marker_names_.begin(); it < marker_names_.end(); it++)
323  {
324  it->active = false;
325  }
326 
327  // for each cluster, see if it is a block
328  for (size_t c = 0; c < clusters.size (); ++c)
329  {
330  // find cluster centroid/color
331  float x = 0; float y = 0; float z = 0; int r = 0; int g = 0; int b = 0;
332  for (size_t i = 0; i < clusters[c].indices.size(); i++)
333  {
334  int j = clusters[c].indices[i];
335  x += cloud_filtered->points[j].x;
336  y += cloud_filtered->points[j].y;
337  z += cloud_filtered->points[j].z;
338 
339  r += cloud_filtered->points[j].r;
340  g += cloud_filtered->points[j].g;
341  b += cloud_filtered->points[j].b;
342  }
343  x = x/clusters[c].indices.size();
344  y = y/clusters[c].indices.size();
345  z = z/clusters[c].indices.size();
346 
347  r = r/clusters[c].indices.size();
348  g = g/clusters[c].indices.size();
349  b = b/clusters[c].indices.size();
350 
351  bool new_ = true;
352  // see if we have it detected
353  for( std::vector<Block>::iterator it=marker_names_.begin(); it < marker_names_.end(); it++)
354  {
355  if( (fabs(it->x - x) < block_size*2) &&
356  (fabs(it->y - y) < block_size*2) )
357  {
358  new_ = false;
359  it->active = true;
360  break;
361  }
362  }
363 
364  if (new_){
365  // else, add new block
366  addBlock( x, y, z - block_size, 0.0, (float) r/255.0, (float) g/255.0, (float) b/255.0, markers_++ );
367  }
368  }
369 
370  // need to delete old blocks
371  for( std::vector<Block>::iterator it=marker_names_.begin(); it < marker_names_.end(); )
372  {
373  if(it->active or it->getName() == last_block_){
374  it++;
375  }else{
376  server.erase( it->getName() );
377  it = marker_names_.erase(it);
378  }
379  }
380 
381  server.applyChanges();
382 }
383 
384 };
385 
386 int main(int argc, char** argv)
387 {
388  // initialize node
389  ros::init(argc, argv, "block_manipulation");
390 
391  BlockManipulation manip;
392 
393  // everything is done in cloud callback, just spin
394  ros::spin();
395 }
396 
const double z_down
tf::TransformListener tf_listener_
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())
std::string getName()
interactive_markers::InteractiveMarkerServer server
bool waitForResult(const ros::Duration &timeout=ros::Duration(0, 0))
bool sleep() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
Block(const Block &b)
const double gripper_closed
TFSIMD_FORCE_INLINE const tfScalar & getW() const
double y
ROSCPP_DECL void spin(Spinner &spinner)
const double z_up
bool waitForTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
void cloudCb(const sensor_msgs::PointCloud2ConstPtr &msg)
Marker makeBox(InteractiveMarker &msg)
void moveBlock(const InteractiveMarkerFeedbackConstPtr &feedback)
void addBlock(float x, float y, float z, float rz, float r, float g, float b, int n)
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
actionlib::SimpleActionClient< simple_arm_server::MoveArmAction > client_
#define ROS_INFO(...)
std::vector< Block > marker_names_
double z
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
r
action
Marker makeBox(InteractiveMarker &msg, float r, float g, float b)
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
void insert(const visualization_msgs::InteractiveMarker &int_marker)
#define ROS_INFO_STREAM(args)
void transformPointCloud(const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const tf::Transform &transform)
int main(int argc, char **argv)
bool setCallback(const std::string &name, FeedbackCallback feedback_cb, uint8_t feedback_type=DEFAULT_FEEDBACK_CB)
Block(int _id, double _x, double _y)
const std::string arm_link
double x
const double block_size
#define ROS_ERROR(...)
bool erase(const std::string &name)
const double gripper_open
ros::Subscriber sub_


turtlebot_arm_block_manipulation
Author(s): Michael Ferguson, Helen Oleynikova
autogenerated on Fri Feb 7 2020 03:56:21