45 DiagnosticNodelet::onInit();
48 std::vector<double> direction;
53 jsk_recognition_utils::pointFromVectorToVector<std::vector<double>, Eigen::Vector3f>(
60 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
61 dynamic_reconfigure::Server<Config>::CallbackType
f =
64 srv_->setCallback (f);
66 pub_ = advertise<PCLIndicesMsg>(*
pnh_,
"output", 1);
86 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(
queue_size_);
104 const pcl::PointCloud<pcl::Normal>::Ptr& normal_cloud,
105 const Eigen::Vector3f& direction,
106 pcl::PointIndices& indices)
108 for (
size_t i = 0; i < normal_cloud->points.size(); i++) {
109 Eigen::Vector3f normal = normal_cloud->points[i].getNormalVector3fMap().normalized();
110 if (!std::isnan(normal[0]) &&
111 !std::isnan(normal[1]) &&
112 !std::isnan(normal[2])) {
113 double dot = std::abs(normal.dot(direction));
117 else if (dot > 1.0) {
123 indices.indices.push_back(i);
130 const sensor_msgs::PointCloud2::ConstPtr&
msg,
131 const sensor_msgs::Imu::ConstPtr& imu_msg)
135 pcl::PointCloud<pcl::Normal>::Ptr normal(
new pcl::PointCloud<pcl::Normal>);
137 geometry_msgs::Vector3Stamped stamped_imu, transformed_imu;
138 stamped_imu.header = imu_msg->header;
139 stamped_imu.vector = imu_msg->linear_acceleration;
145 msg->header.frame_id, stamped_imu, transformed_imu);
146 Eigen::Vector3d imu_vectord;
147 Eigen::Vector3f imu_vector;
149 jsk_recognition_utils::pointFromVectorToVector<Eigen::Vector3d, Eigen::Vector3f>(
150 imu_vectord, imu_vector);
151 imu_vector.normalize();
152 pcl::PointIndices indices;
154 pcl_msgs::PointIndices ros_indices;
156 ros_indices.header = msg->header;
161 NODELET_ERROR(
"[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
165 NODELET_ERROR(
"[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
169 NODELET_ERROR(
"[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
174 const sensor_msgs::PointCloud2::ConstPtr&
msg)
178 pcl::PointCloud<pcl::Normal>::Ptr normal(
new pcl::PointCloud<pcl::Normal>);
181 pcl::PointIndices indices;
183 pcl_msgs::PointIndices ros_indices;
185 ros_indices.header = msg->header;
virtual void configCallback(Config &config, uint32_t level)
virtual void filterIndices(const pcl::PointCloud< pcl::Normal >::Ptr &normal, const Eigen::Vector3f &direction, pcl::PointIndices &indices)
#define NODELET_ERROR(...)
void publish(const boost::shared_ptr< M > &message) const
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
T dot(T *pf1, T *pf2, int length)
tf::TransformListener * tf_listener_
message_filters::Subscriber< sensor_msgs::Imu > sub_imu_
void vectorMsgToEigen(const geometry_msgs::Vector3 &m, Eigen::Vector3d &e)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::NormalDirectionFilter, nodelet::Nodelet)
NormalDirectionFilterConfig Config
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
INLINE Rall1d< T, V, S > acos(const Rall1d< T, V, S > &x)
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
Eigen::Vector3f static_direction_
virtual void filter(const sensor_msgs::PointCloud2::ConstPtr &msg)
static tf::TransformListener * getInstance()
virtual void unsubscribe()
std_msgs::Header fromPCL(const pcl::PCLHeader &pcl_header)