37 #ifndef JSK_PCL_ROS_INTERACTIVE_CUBOID_LIKELIHOOD_H_ 38 #define JSK_PCL_ROS_INTERACTIVE_CUBOID_LIKELIHOOD_H_ 42 #include <jsk_pcl_ros/InteractiveCuboidLikelihoodConfig.h> 43 #include <dynamic_reconfigure/server.h> 44 #include <visualization_msgs/Marker.h> 45 #include <std_msgs/Float32.h> 53 typedef InteractiveCuboidLikelihoodConfig
Config;
61 virtual void likelihood(
const sensor_msgs::PointCloud2::ConstPtr&
msg);
62 virtual void processFeedback(
const visualization_msgs::InteractiveMarkerFeedback::ConstPtr& feedback);
63 virtual void processPlaneFeedback(
const visualization_msgs::InteractiveMarkerFeedback::ConstPtr& feedback);
InteractiveCuboidLikelihoodConfig Config
virtual void processFeedback(const visualization_msgs::InteractiveMarkerFeedback::ConstPtr &feedback)
virtual visualization_msgs::Marker particleToMarker(const Particle &p)
virtual visualization_msgs::InteractiveMarker particleToInteractiveMarker(const Particle &p)
boost::shared_ptr< interactive_markers::InteractiveMarkerServer > plane_server_
virtual void processPlaneFeedback(const visualization_msgs::InteractiveMarkerFeedback::ConstPtr &feedback)
Eigen::Affine3f plane_pose_
tf::TransformListener * tf_
Eigen::Vector3f viewpoint_
virtual visualization_msgs::InteractiveMarker planeInteractiveMarker()
std::string sensor_frame_
boost::mutex mutex
global mutex.
virtual void likelihood(const sensor_msgs::PointCloud2::ConstPtr &msg)
boost::shared_ptr< InteractiveCuboidLikelihood > Ptr
virtual void unsubscribe()
InteractiveCuboidLikelihood()
pcl::tracking::ParticleCuboid Particle
virtual void configCallback(Config &config, uint32_t level)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
boost::shared_ptr< interactive_markers::InteractiveMarkerServer > server_