47 nr_parameter_(nr_parameter),
69 pcl::PointCloud<pcl::PointXYZ>::Ptr output)
71 Eigen::Vector3f transf(
pose_.translation());
72 ROS_DEBUG(
"%s transf: %f %f %f", __FUNCTION__, transf[0], transf[1], transf[2]);
73 output->points.clear();
74 for (
size_t i = 0; i < input->points.size(); i++) {
75 pcl::PointXYZ
p = input->points[i];
76 if (!std::isnan(p.x) && !std::isnan(p.y) && !std::isnan(p.z)) {
78 output->points.push_back(p);
104 Eigen::Vector3f
pos = p.getVector3fMap();
105 Eigen::Vector3f origin(
pose_.translation());
106 double distance = (pos - origin).norm();
131 return "SphereCropper";
136 visualization_msgs::Marker
marker;
137 marker.type = visualization_msgs::Marker::SPHERE;
141 marker.color.r = 0.5;
142 marker.color.g = 0.5;
143 marker.color.b = 0.5;
144 marker.color.a = 0.5;
160 return "CubeCropper";
165 visualization_msgs::Marker
marker;
166 marker.type = visualization_msgs::Marker::CUBE;
170 marker.color.r = 0.5;
171 marker.color.g = 0.5;
172 marker.color.b = 0.5;
173 marker.color.a = 0.5;
201 Eigen::Vector3f
pos = p.getVector3fMap();
202 Eigen::Vector3f
diff = pos -
pose_.translation();
217 cropper_candidates_.push_back(std::make_shared<SphereCropper>());
218 cropper_candidates_.push_back(std::make_shared<CubeCropper>());
219 cropper_ = cropper_candidates_[0];
220 point_pub_ = pnh.
advertise<sensor_msgs::PointCloud2>(
"output", 1);
221 point_visualization_pub_ = pnh.
advertise<sensor_msgs::PointCloud2>(
222 "visualization_pointcloud", 1);
225 initializeInteractiveMarker();
226 srv_ = std::make_shared <dynamic_reconfigure::Server<Config> > (pnh);
227 dynamic_reconfigure::Server<Config>::CallbackType
f =
229 srv_->setCallback (f);
240 boost::mutex::scoped_lock
lock(mutex_);
241 for (
size_t i = 0; i < cropper_candidates_.size(); i++) {
242 cropper_candidates_[i]->updateParameter(config.param0, 0);
243 cropper_candidates_[i]->updateParameter(config.param1, 1);
244 cropper_candidates_[i]->updateParameter(config.param2, 2);
246 reInitializeInteractiveMarker();
250 const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
252 boost::mutex::scoped_lock
lock(mutex_);
253 geometry_msgs::PoseStamped input_pose_stamped, transformed_pose_stamped;
254 input_pose_stamped.pose = feedback->pose;
255 input_pose_stamped.header.stamp = feedback->header.stamp;
256 input_pose_stamped.header.frame_id = feedback->header.frame_id;
257 if (!latest_pointcloud_) {
258 ROS_WARN(
"no pointcloud is available yet");
263 tf_listener_->transformPose(
264 latest_pointcloud_->header.frame_id,
266 transformed_pose_stamped);
272 Eigen::Affine3d pose_d;
275 Eigen::Vector3d transd(pose_d.translation());
276 Eigen::Quaterniond rotated(pose_d.rotation());
277 Eigen::Vector3f transf(transd[0], transd[1], transd[2]);
278 Eigen::Quaternionf rotatef(rotated.w(),
279 rotated.x(), rotated.y(), rotated.z());
280 Eigen::Affine3f pose_f = Eigen::Translation3f(transf) * rotatef;
281 ROS_DEBUG(
"transf: %f %f %f", transf[0], transf[1], transf[2]);
282 cropper_->setPose(pose_f);
284 cropAndPublish(point_visualization_pub_);
289 pcl::PointCloud<pcl::PointXYZ>::Ptr input
290 (
new pcl::PointCloud<pcl::PointXYZ>);
291 pcl::PointCloud<pcl::PointXYZ>::Ptr output
292 (
new pcl::PointCloud<pcl::PointXYZ>);
294 cropper_->crop(input, output);
296 sensor_msgs::PointCloud2 ros_output;
298 ros_output.header = latest_pointcloud_->header;
303 Eigen::Affine3f pose_offset)
305 updateInteractiveMarker();
307 menu_handler_.insert(
312 = menu_handler_.insert(
"Switch");
313 cropper_entries_.clear();
314 for (
size_t i = 0; i < cropper_candidates_.size(); i++) {
317 = menu_handler_.insert(
318 sub_cropper_menu_handle, the_cropper->getName(),
320 if (the_cropper != cropper_) {
321 menu_handler_.setCheckState(
326 menu_handler_.setCheckState(
330 cropper_entries_.push_back(cropper_entry);
332 menu_handler_.apply(*server_,
"pointcloud cropper");
333 server_->applyChanges();
339 updateInteractiveMarker(cropper_->getPose());
341 updateMenuCheckboxStatus();
342 menu_handler_.reApply(*server_);
343 server_->applyChanges();
348 Eigen::Affine3f pose_offset)
350 visualization_msgs::InteractiveMarker int_marker;
351 if (latest_pointcloud_) {
352 int_marker.header.frame_id = latest_pointcloud_->header.frame_id;
355 int_marker.header.frame_id =
"/camera_link";
357 int_marker.name =
"pointcloud cropper";
358 int_marker.description = cropper_->getName();
359 visualization_msgs::InteractiveMarkerControl control;
360 control.always_visible =
true;
361 visualization_msgs::Marker cropper_marker = cropper_->getMarker();
362 control.interaction_mode
363 = visualization_msgs::InteractiveMarkerControl::BUTTON;
364 control.markers.push_back(cropper_marker);
365 int_marker.controls.push_back(control);
367 Eigen::Vector3f offset_pos(pose_offset.translation());
368 Eigen::Quaternionf offset_rot(pose_offset.rotation());
369 int_marker.pose.position.x = offset_pos[0];
370 int_marker.pose.position.y = offset_pos[1];
371 int_marker.pose.position.z = offset_pos[2];
372 int_marker.pose.orientation.x = offset_rot.x();
373 int_marker.pose.orientation.y = offset_rot.y();
374 int_marker.pose.orientation.z = offset_rot.z();
375 int_marker.pose.orientation.w = offset_rot.w();
376 control.markers.push_back(cropper_marker);
377 ROS_DEBUG(
"pos: %f, %f, %f", int_marker.pose.position.x,
378 int_marker.pose.position.y,
379 int_marker.pose.position.z);
380 ROS_DEBUG(
"rot: %f.; %f, %f, %f", int_marker.pose.orientation.w,
381 int_marker.pose.orientation.x,
382 int_marker.pose.orientation.y,
383 int_marker.pose.orientation.z);
388 server_->insert(int_marker,
393 const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback )
395 unsigned int menu_entry_id = feedback->menu_entry_id;
396 EntryHandleVector::iterator it = std::find(cropper_entries_.begin(),
397 cropper_entries_.end(),
399 size_t index = std::distance(cropper_entries_.begin(), it);
400 if (index >= cropper_candidates_.size()) {
401 ROS_ERROR(
"the index of the chosen cropper is out of the" 402 "range of candidate");
406 if (next_cropper == cropper_) {
411 changeCropper(next_cropper);
417 for (
size_t i = 0; i < cropper_candidates_.size(); i++) {
419 if (the_cropper == cropper_) {
420 menu_handler_.setCheckState(
425 menu_handler_.setCheckState(
434 next_cropper->setPose(cropper_->getPose());
435 cropper_ = next_cropper;
437 reInitializeInteractiveMarker();
441 const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
443 unsigned int menu_entry_id = feedback->menu_entry_id;
444 if (menu_entry_id == 1) {
445 cropAndPublish(point_pub_);
451 boost::mutex::scoped_lock
lock(mutex_);
452 latest_pointcloud_ = msg;
453 cropAndPublish(point_visualization_pub_);
457 int main(
int argc,
char** argv)
459 ros::init(argc, argv,
"pointcloud_cropper");
virtual void inputCallback(const sensor_msgs::PointCloud2::ConstPtr &msg)
virtual ~PointCloudCropper()
virtual visualization_msgs::Marker getMarker()
unsigned int nr_parameter_
virtual void menuFeedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
std::shared_ptr< Cropper > Ptr
void publish(const boost::shared_ptr< M > &message) const
virtual void changeCropper(Cropper::Ptr next_cropper)
Cropper(const unsigned int nr_parameter)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
virtual void initializeInteractiveMarker(Eigen::Affine3f pose_offset=Eigen::Affine3f::Identity())
virtual void processFeedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
ROSCPP_DECL const std::string & getName()
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
TFSIMD_FORCE_INLINE tfScalar distance(const Vector3 &v) const
virtual visualization_msgs::Marker getMarker()
PointCloudCropperConfig Config
virtual void setPose(Eigen::Affine3f pose)
std::vector< double > parameters_
ROSCPP_DECL void spin(Spinner &spinner)
virtual bool isInside(const pcl::PointXYZ &p)
virtual double getWidthX()
virtual void changeCropperCallback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
virtual Eigen::Affine3f getPose()
virtual double getWidthZ()
virtual std::string getName()
virtual void updateMenuCheckboxStatus()
virtual void crop(const pcl::PointCloud< pcl::PointXYZ >::Ptr &input, pcl::PointCloud< pcl::PointXYZ >::Ptr output)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
virtual bool isInside(const pcl::PointXYZ &p)
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
#define ROS_DEBUG_STREAM(args)
virtual void fillInitialParameters()
virtual void updateInteractiveMarker(Eigen::Affine3f pose_offset=Eigen::Affine3f::Identity())
virtual double getWidthY()
virtual void updateParameter(const double val, const unsigned int index)
virtual std::string getName()
void add6DofControl(visualization_msgs::InteractiveMarker &msg, bool fixed=false)
int main(int argc, char **argv)
virtual void configCallback(Config &config, uint32_t level)
PointCloudCropper(ros::NodeHandle &nh, ros::NodeHandle &pnh)
virtual void fillInitialParameters()
virtual void cropAndPublish(ros::Publisher &pub)
virtual bool isInside(const pcl::PointXYZ &p)=0
virtual void reInitializeInteractiveMarker()
virtual double getRadius()