Go to the documentation of this file.
36 #define BOOST_PARAMETER_MAX_ARITY 7
42 #include <jsk_topic_tools/rosparam_utils.h>
48 DiagnosticNodelet::onInit();
50 ROS_ERROR(
"You need to specify ~target_frame_id");
54 std::vector<double> axis(3);
55 if (!jsk_topic_tools::readVectorParameter(*pnh_,
"axis", axis)) {
64 pub_ = advertise<jsk_recognition_msgs::PolygonArray>(*pnh_,
"output", 1);
86 const jsk_recognition_msgs::PolygonArray::ConstPtr& msg)
89 vital_checker_->poke();
90 jsk_recognition_msgs::PolygonArray new_msg(*
msg);
100 Eigen::Affine3f
pose;
104 Eigen::Vector3f reference_axis =
pose.rotation() *
axis_;
106 double min_distance = DBL_MAX;
107 double max_distance = - DBL_MAX;
108 std::vector<double> distances;
109 for (
size_t i = 0;
i <
msg->polygons.size();
i++) {
112 Eigen::Vector3f n = polygon->getNormal();
113 double distance = std::abs(reference_axis.dot(n));
114 min_distance = std::min(
distance, min_distance);
115 max_distance = std::max(
distance, max_distance);
120 for (
size_t i = 0;
i < distances.size();
i++) {
123 double likelihood = 1 / (1 + (distances[
i] - 1) * (distances[
i] - 1));
125 if (
msg->likelihood.size() == 0) {
129 new_msg.likelihood[
i] = new_msg.likelihood[
i] *
likelihood;
#define NODELET_ERROR(...)
virtual void unsubscribe()
template Halfspace< double > transform(const Halfspace< double > &a, const Transform3< double > &tf)
void publish(const boost::shared_ptr< M > &message) const
boost::shared_ptr< tf::MessageFilter< jsk_recognition_msgs::PolygonArray > > tf_filter_
void transformTFToEigen(const tf::Transform &t, Eigen::Affine3f &eigen)
std::string target_frame_id_
tf::TransformListener * tf_listener_
template void distance(DistanceTraversalNodeBase< double > *node, BVHFrontList *front_list, int qsize)
virtual void likelihood(const jsk_recognition_msgs::PolygonArray::ConstPtr &msg)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::PolygonArrayAngleLikelihood, nodelet::Nodelet)
static Polygon::Ptr fromROSMsgPtr(const geometry_msgs::Polygon &polygon)
static tf::TransformListener * getInstance()
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_
jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Fri May 16 2025 03:11:43