18 #ifndef CONVERTER_CAMERA_HPP    19 #define CONVERTER_CAMERA_HPP    40   typedef boost::function<void(sensor_msgs::ImagePtr, sensor_msgs::CameraInfo)> 
Callback_t;
    44     const std::string& 
name,
    46     const qi::SessionPtr& session,
    47     const int& camera_source,
    48     const int& resolution,
    49     const bool& has_stereo=
false);
    57   void callAll( 
const std::vector<message_actions::MessageAction>& actions );
    60   std::map<message_actions::MessageAction, Callback_t> 
callbacks_;
    76   sensor_msgs::ImagePtr 
msg_;
 
void callAll(const std::vector< message_actions::MessageAction > &actions)
sensor_msgs::CameraInfo camera_info_
CameraConverter(const std::string &name, const float &frequency, const qi::SessionPtr &session, const int &camera_source, const int &resolution, const bool &has_stereo=false)
void registerCallback(const message_actions::MessageAction action, Callback_t cb)
boost::function< void(sensor_msgs::ImagePtr, sensor_msgs::CameraInfo)> Callback_t
std::string msg_colorspace_
std::map< message_actions::MessageAction, Callback_t > callbacks_
sensor_msgs::ImagePtr msg_