Go to the documentation of this file.
36 #define BOOST_PARAMETER_MAX_ARITY 7
47 DiagnosticNodelet::onInit();
49 ROS_ERROR(
"You need to specify ~target_frame_id");
54 pub_ = advertise<jsk_recognition_msgs::PolygonArray>(*pnh_,
"output", 1);
77 const jsk_recognition_msgs::PolygonArray::ConstPtr& msg)
80 vital_checker_->poke();
81 jsk_recognition_msgs::PolygonArray new_msg(*
msg);
93 Eigen::Vector3f
p(
pose.translation());
95 double min_distance = DBL_MAX;
96 double max_distance = - DBL_MAX;
97 std::vector<double> distances;
98 for (
size_t i = 0;
i <
msg->polygons.size();
i++) {
103 min_distance = std::min(
distance, min_distance);
104 max_distance = std::max(
distance, max_distance);
109 for (
size_t i = 0;
i < distances.size();
i++) {
112 double likelihood = 1 / (1 + distances[
i] * distances[
i]);
114 if (
msg->likelihood.size() == 0) {
118 new_msg.likelihood[
i] = new_msg.likelihood[
i] *
likelihood;
#define NODELET_ERROR(...)
tf::TransformListener * tf_listener_
virtual void likelihood(const jsk_recognition_msgs::PolygonArray::ConstPtr &msg)
template Halfspace< double > transform(const Halfspace< double > &a, const Transform3< double > &tf)
void publish(const boost::shared_ptr< M > &message) const
virtual void unsubscribe()
std::string target_frame_id_
void transformTFToEigen(const tf::Transform &t, Eigen::Affine3f &eigen)
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_
template void distance(DistanceTraversalNodeBase< double > *node, BVHFrontList *front_list, int qsize)
boost::shared_ptr< tf::MessageFilter< jsk_recognition_msgs::PolygonArray > > tf_filter_
static Polygon::Ptr fromROSMsgPtr(const geometry_msgs::Polygon &polygon)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::PolygonArrayDistanceLikelihood, nodelet::Nodelet)
static tf::TransformListener * getInstance()
jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Fri May 16 2025 03:11:43