33 #include <sensor_msgs/PointCloud2.h> 36 #include <simple_arm_server/MoveArmAction.h> 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> 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) {}
78 std::stringstream conv;
80 return std::string(
"block") + conv.str();
108 last_block_ = std::string(
"");
115 simple_arm_server::MoveArmGoal goal;
116 simple_arm_server::ArmAction grip;
117 grip.type = simple_arm_server::ArmAction::MOVE_GRIPPER;
119 goal.motions.push_back(grip);
126 pub_ = nh.
advertise< pcl::PointCloud<pcl::PointXYZRGB> >(
"block_output", 1);
134 void moveBlock(
const InteractiveMarkerFeedbackConstPtr &feedback )
136 switch ( feedback->event_type )
138 case visualization_msgs::InteractiveMarkerFeedback::MOUSE_DOWN:
140 x_ = feedback->pose.position.x;
141 y_ = feedback->pose.position.y;
142 last_block_ = feedback->marker_name;
145 case visualization_msgs::InteractiveMarkerFeedback::MOUSE_UP:
149 simple_arm_server::MoveArmGoal goal;
150 simple_arm_server::ArmAction
action;
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();
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;
168 action.goal.position.z =
z_down;
169 goal.motions.push_back(action);
170 action.move_time.sec = 1.5;
173 simple_arm_server::ArmAction grip;
174 grip.type = simple_arm_server::ArmAction::MOVE_GRIPPER;
176 grip.move_time.sec = 1.0;
177 goal.motions.push_back(grip);
180 action.goal.position.z =
z_up;
181 goal.motions.push_back(action);
182 action.move_time.sec = 0.25;
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;
192 action.goal.position.z =
z_down;
193 goal.motions.push_back(action);
194 action.move_time.sec = 1.5;
198 goal.motions.push_back(grip);
201 action.goal.position.z =
z_up;
202 goal.motions.push_back(action);
203 action.move_time.sec = 0.25;
209 for( std::vector<Block>::iterator it=marker_names_.begin(); it < marker_names_.end(); it++)
211 if( it->getName() == feedback->marker_name )
213 it->x = feedback->pose.position.x;
214 it->y = feedback->pose.position.y;
227 Marker
makeBox( InteractiveMarker &msg,
float r,
float g,
float b )
231 m.type = Marker::CUBE;
232 m.scale.x = msg.scale;
233 m.scale.y = msg.scale;
234 m.scale.z = msg.scale;
244 void addBlock(
float x,
float y,
float z,
float rz,
float r,
float g,
float b,
int n)
246 InteractiveMarker marker;
248 marker.pose.position.x = x;
249 marker.pose.position.y = y;
250 marker.pose.position.z = z;
253 Block block( n, x, y );
254 marker_names_.push_back( block );
256 marker.description =
"Another block";
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 );
266 control.markers.push_back(
makeBox(marker, r, g, b) );
267 control.always_visible =
true;
268 marker.controls.push_back( control );
276 void cloudCb (
const sensor_msgs::PointCloud2ConstPtr& msg )
278 if( (skip_++)%15 != 0 )
return;
281 pcl::PointCloud<pcl::PointXYZRGB> cloud;
285 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_transformed (
new pcl::PointCloud<pcl::PointXYZRGB>);
290 ROS_ERROR (
"Error converting to base_link");
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");
300 pass.filter(*cloud_filtered);
301 if( cloud_filtered->points.size() == 0 ){
305 ROS_INFO(
"Filtered, %d points left", (
int) cloud_filtered->points.size());
309 pcl::search::KdTree<pcl::PointXYZRGB>::Ptr tree (
new pcl::search::KdTree<pcl::PointXYZRGB>);
310 tree->setInputCloud(cloud_filtered);
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);
322 for( std::vector<Block>::iterator it=marker_names_.begin(); it < marker_names_.end(); it++)
328 for (
size_t c = 0; c < clusters.size (); ++c)
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++)
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;
339 r += cloud_filtered->points[j].r;
340 g += cloud_filtered->points[j].g;
341 b += cloud_filtered->points[j].b;
343 x = x/clusters[c].indices.size();
344 y = y/clusters[c].indices.size();
345 z = z/clusters[c].indices.size();
347 r = r/clusters[c].indices.size();
348 g = g/clusters[c].indices.size();
349 b = b/clusters[c].indices.size();
353 for( std::vector<Block>::iterator it=marker_names_.begin(); it < marker_names_.end(); it++)
366 addBlock( x, y, z -
block_size, 0.0, (
float) r/255.0, (
float) g/255.0, (
float) b/255.0, markers_++ );
371 for( std::vector<Block>::iterator it=marker_names_.begin(); it < marker_names_.end(); )
373 if(it->active or it->getName() == last_block_){
376 server.
erase( it->getName() );
377 it = marker_names_.erase(it);
386 int main(
int argc,
char** argv)
389 ros::init(argc, argv,
"block_manipulation");
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())
interactive_markers::InteractiveMarkerServer server
bool waitForResult(const ros::Duration &timeout=ros::Duration(0, 0))
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)
const double gripper_closed
TFSIMD_FORCE_INLINE const tfScalar & getW() const
ROSCPP_DECL void spin(Spinner &spinner)
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_
std::vector< Block > marker_names_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
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
bool erase(const std::string &name)
const double gripper_open