47 nr_parameter_(nr_parameter),
50 parameters_.resize(nr_parameter_);
58 void Cropper::setPose(Eigen::Affine3f pose)
68 void Cropper::crop(
const pcl::PointCloud<pcl::PointXYZ>::Ptr& input,
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);
85 void Cropper::updateParameter(
const double param,
const unsigned int index)
87 if (parameters_.size() >=
index + 1) {
92 SphereCropper::SphereCropper():
Cropper(1)
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;
160 return "CubeCropper";
165 visualization_msgs::Marker
marker;
166 marker.type = visualization_msgs::Marker::CUBE;
201 Eigen::Vector3f
pos =
p.getVector3fMap();
202 Eigen::Vector3f diff =
pos -
pose_.translation();
222 "visualization_pointcloud", 1);
226 srv_ = std::make_shared <dynamic_reconfigure::Server<Config> > (pnh);
227 dynamic_reconfigure::Server<Config>::CallbackType
f =
229 srv_->setCallback (f);
250 const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
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;
258 ROS_WARN(
"no pointcloud is available yet");
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]);
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>);
296 sensor_msgs::PointCloud2 ros_output;
299 pub.publish(ros_output);
303 Eigen::Affine3f pose_offset)
318 sub_cropper_menu_handle, the_cropper->getName(),
348 Eigen::Affine3f pose_offset)
350 visualization_msgs::InteractiveMarker int_marker;
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);
393 const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback )
395 unsigned int menu_entry_id = feedback->menu_entry_id;
401 ROS_ERROR(
"the index of the chosen cropper is out of the"
402 "range of candidate");
434 next_cropper->setPose(
cropper_->getPose());
441 const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
443 unsigned int menu_entry_id = feedback->menu_entry_id;
444 if (menu_entry_id == 1) {
457 int main(
int argc,
char** argv)