#include <camera.hpp>

Public Member Functions | |
| void | callAll (const std::vector< message_actions::MessageAction > &actions) |
| 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) |
| void | reset () |
| ~CameraConverter () | |
Public Member Functions inherited from naoqi::converter::BaseConverter< CameraConverter > | |
| BaseConverter (const std::string &name, float frequency, qi::SessionPtr session) | |
| float | frequency () const |
| std::string | name () const |
| virtual | ~BaseConverter () |
Private Types | |
| typedef boost::function< void(sensor_msgs::ImagePtr, sensor_msgs::CameraInfo)> | Callback_t |
Private Attributes | |
| std::map< message_actions::MessageAction, Callback_t > | callbacks_ |
| sensor_msgs::CameraInfo | camera_info_ |
| int | camera_source_ |
| int | colorspace_ |
| int | cv_mat_type_ |
| std::string | handle_ |
| sensor_msgs::ImagePtr | msg_ |
| std::string | msg_colorspace_ |
| std::string | msg_frameid_ |
| qi::AnyObject | p_video_ |
| int | resolution_ |
Additional Inherited Members | |
Protected Attributes inherited from naoqi::converter::BaseConverter< CameraConverter > | |
| float | frequency_ |
| std::string | name_ |
| bool | record_enabled_ |
| const robot::Robot & | robot_ |
| qi::SessionPtr | session_ |
Definition at line 37 of file converters/camera.hpp.
|
private |
Definition at line 40 of file converters/camera.hpp.
| naoqi::converter::CameraConverter::CameraConverter | ( | const std::string & | name, |
| const float & | frequency, | ||
| const qi::SessionPtr & | session, | ||
| const int & | camera_source, | ||
| const int & | resolution, | ||
| const bool & | has_stereo = false |
||
| ) |
Definition at line 183 of file converters/camera.cpp.
| naoqi::converter::CameraConverter::~CameraConverter | ( | ) |
Definition at line 231 of file converters/camera.cpp.
| void naoqi::converter::CameraConverter::callAll | ( | const std::vector< message_actions::MessageAction > & | actions | ) |
Definition at line 264 of file converters/camera.cpp.
| void naoqi::converter::CameraConverter::registerCallback | ( | const message_actions::MessageAction | action, |
| Callback_t | cb | ||
| ) |
Definition at line 259 of file converters/camera.cpp.
| void naoqi::converter::CameraConverter::reset | ( | ) |
Definition at line 241 of file converters/camera.cpp.
|
private |
Definition at line 60 of file converters/camera.hpp.
|
private |
Definition at line 75 of file converters/camera.hpp.
|
private |
Definition at line 64 of file converters/camera.hpp.
|
private |
Definition at line 66 of file converters/camera.hpp.
|
private |
Definition at line 72 of file converters/camera.hpp.
|
private |
Definition at line 67 of file converters/camera.hpp.
|
private |
Definition at line 76 of file converters/camera.hpp.
|
private |
Definition at line 71 of file converters/camera.hpp.
|
private |
Definition at line 74 of file converters/camera.hpp.
|
private |
VideoDevice (Proxy) configurations
Definition at line 63 of file converters/camera.hpp.
|
private |
Definition at line 65 of file converters/camera.hpp.