35 #define BOOST_PARAMETER_MAX_ARITY 7 39 #include <jsk_recognition_msgs/BoundingBox.h> 46 DiagnosticNodelet::onInit();
49 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
50 dynamic_reconfigure::Server<Config>::CallbackType
f =
54 pub_ = advertise<jsk_recognition_msgs::BoundingBox>(*
pnh_,
"output", 1);
59 Config &config, uint32_t level)
76 const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& bbox_array_msg)
80 jsk_recognition_msgs::BoundingBox bbox_msg;
81 bbox_msg.header = bbox_array_msg->header;
83 int array_size = bbox_array_msg->boxes.size();
86 }
else if (
index_ < array_size) {
87 bbox_msg = bbox_array_msg->boxes[
index_];
virtual void unsubscribe()
void publish(const boost::shared_ptr< M > &message) const
#define NODELET_ERROR_THROTTLE(rate,...)
virtual void convert(const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &bbox_array_msg)
virtual void configCallback(Config &config, uint32_t level)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::BoundingBoxArrayToBoundingBox, nodelet::Nodelet)
jsk_pcl_ros_utils::BoundingBoxArrayToBoundingBoxConfig Config
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_