39 #include <geometry_msgs/Vector3Stamped.h> 46 ConnectionBasedNodelet::onInit();
50 pnh_->param(
"vital_rate", vital_rate, 1.0);
68 std::vector<double> reference_axis;
70 *
pnh_,
"reference_axis", reference_axis)) {
74 else if (reference_axis.size() != 3){
83 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
84 dynamic_reconfigure::Server<Config>::CallbackType
f =
86 srv_->setCallback (f);
88 polygons_pub_ = advertise<jsk_recognition_msgs::PolygonArray>(
89 *
pnh_,
"output_polygons", 1);
91 *
pnh_,
"output_coefficients", 1);
93 inliers_pub_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(*
pnh_,
"output_inliers", 1);
108 sync_inlier_ = boost::make_shared<message_filters::Synchronizer<SyncInlierPolicy> >(100);
116 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
137 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
138 "PlaneRejector running");
141 stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
142 "failed to tf transform");
148 stat.
add(
"Reference Axis",
149 (boost::format(
"[%f, %f, %f]")
156 stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
157 "PlaneRejector not running");
176 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons,
177 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients)
179 reject(polygons, coefficients, jsk_recognition_msgs::ClusterPointIndices::ConstPtr());
183 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons,
184 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients,
185 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& inliers)
189 jsk_recognition_msgs::PolygonArray result_polygons;
190 jsk_recognition_msgs::ModelCoefficientsArray result_coefficients;
191 jsk_recognition_msgs::ClusterPointIndices result_inliers;
192 result_polygons.header = polygons->header;
193 result_coefficients.header = coefficients->header;
194 result_inliers.header = polygons->header;
196 int rejected_plane_counter = 0;
197 int passed_plane_counter = 0;
198 for (
size_t i = 0; i < polygons->polygons.size(); i++) {
199 geometry_msgs::PolygonStamped polygon = polygons->polygons[i];
204 coefficient.header.stamp)) {
206 geometry_msgs::Vector3Stamped plane_axis;
207 plane_axis.header = coefficient.header;
208 plane_axis.vector.x = coefficient.values[0];
209 plane_axis.vector.y = coefficient.values[1];
210 plane_axis.vector.z = coefficient.values[2];
211 geometry_msgs::Vector3Stamped transformed_plane_axis;
214 transformed_plane_axis);
215 Eigen::Vector3d eigen_transformed_plane_axis;
217 eigen_transformed_plane_axis);
220 eigen_transformed_plane_axis = -eigen_transformed_plane_axis;
224 ++passed_plane_counter;
225 result_polygons.polygons.push_back(polygons->polygons[i]);
226 result_coefficients.coefficients.push_back(coefficient);
228 result_inliers.cluster_indices.push_back(inliers->cluster_indices[i]);
232 ++rejected_plane_counter;
virtual void updateDiagnosticsPlaneRejector(diagnostic_updater::DiagnosticStatusWrapper &stat)
Eigen::Vector3d reference_axis_
jsk_pcl_ros_utils::PlaneRejectorConfig Config
jsk_topic_tools::VitalChecker::Ptr vital_checker_
void publish(const boost::shared_ptr< M > &message) const
ros::Publisher polygons_pub_
void summary(unsigned char lvl, const std::string s)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
const std::string & getName() const
virtual void updateDiagnostics(const ros::TimerEvent &event)
jsk_recognition_utils::Counter passed_plane_counter_
jsk_recognition_utils::SeriesedBoolean::Ptr tf_success_
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_inliers_
virtual void configCallback(Config &config, uint32_t level)
virtual void unsubscribe()
jsk_recognition_utils::Counter rejected_plane_counter_
ros::Publisher coefficients_pub_
std::string processing_frame_id_
void vectorMsgToEigen(const geometry_msgs::Vector3 &m, Eigen::Vector3d &e)
boost::shared_ptr< message_filters::Synchronizer< SyncInlierPolicy > > sync_inlier_
boost::shared_ptr< diagnostic_updater::Updater > diagnostic_updater_
virtual void reject(const jsk_recognition_msgs::PolygonArray::ConstPtr &polygons, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients)
ros::Timer diagnostics_timer_
jsk_recognition_utils::Counter input_plane_counter_
virtual void add(double v)
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)
void pointFromVectorToVector(const FromT &from, ToT &to)
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
ros::Publisher inliers_pub_
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygons_
void add(const std::string &key, const T &val)
static tf::TransformListener * getInstance()
#define NODELET_FATAL(...)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::PlaneRejector, nodelet::Nodelet)
pcl::ModelCoefficients PCLModelCoefficientMsg
tf::TransformListener * listener_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_