37 #ifndef JSK_INTERACTIVE_MARKER_POINTCLOUD_CLOPPER_H_ 38 #define JSK_INTERACTIVE_MARKER_POINTCLOUD_CLOPPER_H_ 40 #define BOOST_PARAMETER_MAX_ARITY 7 // its a hack 47 #include <sensor_msgs/PointCloud2.h> 49 #include <pcl/point_types.h> 50 #include <pcl/point_cloud.h> 51 #include <sensor_msgs/PointCloud2.h> 55 #include <dynamic_reconfigure/server.h> 56 #include <jsk_interactive_marker/PointCloudCropperConfig.h> 64 typedef std::shared_ptr<Cropper>
Ptr;
65 Cropper(
const unsigned int nr_parameter);
68 virtual void crop(
const pcl::PointCloud<pcl::PointXYZ>::Ptr& input,
69 pcl::PointCloud<pcl::PointXYZ>::Ptr output);
70 virtual std::string
getName() = 0;
71 virtual visualization_msgs::Marker
getMarker() = 0;
72 virtual void updateParameter(
const double val,
const unsigned int index);
74 virtual bool isInside(
const pcl::PointXYZ& p) = 0;
76 virtual void setPose(Eigen::Affine3f pose);
77 virtual Eigen::Affine3f
getPose();
90 typedef std::shared_ptr<SphereCropper>
Ptr;
95 virtual visualization_msgs::Marker
getMarker();
96 virtual bool isInside(
const pcl::PointXYZ& p);
98 virtual double getRadius();
107 typedef std::shared_ptr<CubeCropper>
Ptr;
112 virtual visualization_msgs::Marker
getMarker();
113 virtual bool isInside(
const pcl::PointXYZ& p);
115 virtual double getWidthX();
116 virtual double getWidthY();
117 virtual double getWidthZ();
132 typedef std::vector<interactive_markers::MenuHandler::EntryHandle>
135 virtual void inputCallback(
const sensor_msgs::PointCloud2::ConstPtr& msg);
136 virtual void reInitializeInteractiveMarker();
137 virtual void updateInteractiveMarker(
138 Eigen::Affine3f pose_offset = Eigen::Affine3f::Identity());
139 virtual void initializeInteractiveMarker(
140 Eigen::Affine3f pose_offset = Eigen::Affine3f::Identity());
142 const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback);
143 virtual void menuFeedback(
144 const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback);
145 virtual void changeCropperCallback(
146 const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
147 virtual void updateMenuCheckboxStatus();
149 virtual void configCallback(Config &config, uint32_t level);
154 std::shared_ptr<interactive_markers::InteractiveMarkerServer>
server_;
157 std::shared_ptr <dynamic_reconfigure::Server<Config> >
srv_;
unsigned int nr_parameter_
std::shared_ptr< Cropper > Ptr
Cropper(const unsigned int nr_parameter)
sensor_msgs::PointCloud2::ConstPtr latest_pointcloud_
std::shared_ptr< interactive_markers::InteractiveMarkerServer > server_
ros::Subscriber point_sub_
virtual std::string getName()=0
virtual visualization_msgs::Marker getMarker()=0
PointCloudCropperConfig Config
virtual void setPose(Eigen::Affine3f pose)
ros::Publisher point_pub_
std::vector< double > parameters_
std::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
void processFeedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
virtual Eigen::Affine3f getPose()
std::vector< Cropper::Ptr > cropper_candidates_
virtual void crop(const pcl::PointCloud< pcl::PointXYZ >::Ptr &input, pcl::PointCloud< pcl::PointXYZ >::Ptr output)
std::shared_ptr< CubeCropper > Ptr
virtual void updateParameter(const double val, const unsigned int index)
EntryHandleVector cropper_entries_
ros::Publisher point_visualization_pub_
virtual bool isInside(const pcl::PointXYZ &p)=0
interactive_markers::MenuHandler menu_handler_
std::shared_ptr< tf::TransformListener > tf_listener_
std::shared_ptr< SphereCropper > Ptr
virtual void fillInitialParameters()=0
std::vector< interactive_markers::MenuHandler::EntryHandle > EntryHandleVector