37 #ifndef JSK_PCL_ROS_UTILS_POSE_WITH_COVARIANCE_STAMPED_TO_GAUSSIAN_POINTCLOUD_H_ 38 #define JSK_PCL_ROS_UTILS_POSE_WITH_COVARIANCE_STAMPED_TO_GAUSSIAN_POINTCLOUD_H_ 41 #include <geometry_msgs/PoseWithCovarianceStamped.h> 42 #include <jsk_pcl_ros_utils/PoseWithCovarianceStampedToGaussianPointCloudConfig.h> 43 #include <Eigen/Geometry> 44 #include <dynamic_reconfigure/server.h> 50 typedef PoseWithCovarianceStampedToGaussianPointCloudConfig
Config;
57 virtual void convert(
const geometry_msgs::PoseWithCovarianceStamped::ConstPtr&
msg);
59 virtual float gaussian(
const Eigen::Vector2f& input,
60 const Eigen::Vector2f& mean,
61 const Eigen::Matrix2f& S,
62 const Eigen::Matrix2f& S_inv);
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
virtual void configCallback(Config &config, uint32_t level)
virtual float gaussian(const Eigen::Vector2f &input, const Eigen::Vector2f &mean, const Eigen::Matrix2f &S, const Eigen::Matrix2f &S_inv)
PoseWithCovarianceStampedToGaussianPointCloud()
virtual void convert(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg)
PoseWithCovarianceStampedToGaussianPointCloudConfig Config
virtual void unsubscribe()
std::string normalize_method_