Go to the documentation of this file.
    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> 
   28   void imageCallback(
const jsk_recognition_msgs::SparseImageConstPtr& msg){
 
   32   void do_work(
const jsk_recognition_msgs::SparseImageConstPtr& msg, 
const std::string input_frame_from_msg){
 
   36       _img_ptr->header.frame_id = input_frame_from_msg;
 
   44       bool useData32 = 
false;
 
   56           uint32_t pos = 
msg->data32[
i];
 
   57           x = (uint16_t)(pos >> 16);
 
   60           uint16_t pos = 
msg->data16[
i];
 
   61           x = (uint16_t)(pos >> 8);
 
   62           y = (uint16_t)(pos & (uint8_t)-1);
 
   79     jsk_topic_tools::warnNoRemap(names);
 
  103     _img_ptr.reset(
new sensor_msgs::Image());
 
  
#define NODELET_ERROR(...)
ros::NodeHandle & getNodeHandle() const
void disconnectCb(const image_transport::SingleSubscriberPublisher &)
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
image_transport::Publisher _img_pub
void imageCallback(const jsk_recognition_msgs::SparseImageConstPtr &msg)
void connectCb(const image_transport::SingleSubscriberPublisher &ssp)
PLUGINLIB_EXPORT_CLASS(jsk_perception::SparseImageDecoder, nodelet::Nodelet)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
void publish(const sensor_msgs::Image &message) const
ros::Subscriber _spr_img_sub
boost::shared_ptr< image_transport::ImageTransport > _it
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
void do_work(const jsk_recognition_msgs::SparseImageConstPtr &msg, const std::string input_frame_from_msg)
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
std::vector< std::string > V_string
sensor_msgs::ImagePtr _img_ptr
#define NODELET_DEBUG(...)
jsk_perception
Author(s): Manabu Saito, Ryohei Ueda 
autogenerated on Fri May 16 2025 03:11:17