2 #include <boost/shared_ptr.hpp>
3 #include <boost/assign.hpp>
8 #include <jsk_topic_tools/log_utils.h>
11 #include <jsk_recognition_msgs/SparseImage.h>
35 void do_work(
const sensor_msgs::ImageConstPtr& msg,
const std::string input_frame_from_msg){
37 int channel = enc::numChannels(
msg->encoding);
40 bool useData32 =
false;
41 if (std::max(
msg->width,
msg->height) > 256){
54 for (uint32_t y = 0; y <
msg->height; ++y){
55 for (uint32_t
x = 0;
x <
msg->width; ++
x){
56 if(
msg->data[
x*channel+y*
msg->step] > 125){
57 if (useData32)
_spr_img_ptr->data32.push_back( (
x << 16) | y );
68 NODELET_INFO(
"%d point encoded. encoded area per is %lf%%.", size, (100 * ((
double) size)/(
msg->height*
msg->width)));
86 jsk_topic_tools::warnNoRemap(names);
116 _spr_img_ptr = boost::make_shared<jsk_recognition_msgs::SparseImage>();