#include <ImageSubscription.h>
Public Member Functions | |
void | CallBack (const sensor_msgs::ImageConstPtr &msg_ptr) |
bool | CanSee (RelPose &pose) const |
std::string | GetName () const |
Reading * | GetReading (const long &Frame) |
std::pair< std::string, std::vector< double > > | GetUnformatedCalibrationValues () |
std::string | GetWindowName () |
ImageSubscription () | |
bool | IsCamera () const |
XMLTag * | Save () |
void | Show (const long frame) |
should display the sensors currenbt reading, if wanted | |
bool | Start () |
overwrite to start up the data reading, is called at least once after creation | |
bool | Stop () |
overwrite to stop call this in the destructor if necessary, will be used to shut down cameras | |
~ImageSubscription () | |
Public Attributes | |
MinimalCalibration | m_calib |
Protected Member Functions | |
void | SetData (XMLTag *tag) |
Private Attributes | |
sensor_msgs::CvBridge * | m_bridge |
bool | m_bWindowCreated |
bool | m_grabbing |
ros::Subscriber | m_imageSub |
unsigned int | m_max_cameraImagesStored |
std::string | m_stTopicName |
Definition at line 54 of file ImageSubscription.h.
cop::ImageSubscription::ImageSubscription | ( | ) | [inline] |
Definition at line 57 of file ImageSubscription.h.
cop::ImageSubscription::~ImageSubscription | ( | ) | [inline] |
Definition at line 64 of file ImageSubscription.h.
void ImageSubscription::CallBack | ( | const sensor_msgs::ImageConstPtr & | msg_ptr | ) |
Definition at line 95 of file ImageSubsrciption.cpp.
bool ImageSubscription::CanSee | ( | RelPose & | pose | ) | const [virtual] |
CanSee Checks if a pose is inside the view of this sensor
pose | pose that has to be looked at |
Reimplemented from cop::Sensor.
Definition at line 77 of file ImageSubsrciption.cpp.
std::string cop::ImageSubscription::GetName | ( | ) | const [inline, virtual] |
Get Type of the camera by its Name
Reimplemented from cop::Sensor.
Definition at line 69 of file ImageSubscription.h.
Reading * ImageSubscription::GetReading | ( | const long & | Frame | ) | [virtual] |
GetReading
Frame | frame number, to specify an offset or a specific file |
char* | with an error message in case of failure |
Implements cop::Sensor.
Definition at line 40 of file ImageSubsrciption.cpp.
std::pair< std::string, std::vector<double> > cop::ImageSubscription::GetUnformatedCalibrationValues | ( | ) | [inline] |
Definition at line 141 of file ImageSubscription.h.
std::string ImageSubscription::GetWindowName | ( | ) |
Definition at line 67 of file ImageSubsrciption.cpp.
bool cop::ImageSubscription::IsCamera | ( | ) | const [inline, virtual] |
Can this Sensor be used like a camera, (incl. Calibration, Showing, usw.)
Reimplemented from cop::Sensor.
Definition at line 136 of file ImageSubscription.h.
XMLTag* cop::ImageSubscription::Save | ( | ) | [inline, virtual] |
Implements cop::Sensor.
Definition at line 121 of file ImageSubscription.h.
void ImageSubscription::SetData | ( | XMLTag * | tag | ) | [protected, virtual] |
This can be overwritten to get the data necessary to reconstruct a saved reading
Reimplemented from cop::Sensor.
Definition at line 119 of file ImageSubsrciption.cpp.
void ImageSubscription::Show | ( | const long | frame | ) | [virtual] |
should display the sensors currenbt reading, if wanted
Show
frame | number, to specify an temporal offset or a specific file |
Reimplemented from cop::Sensor.
Definition at line 131 of file ImageSubsrciption.cpp.
bool cop::ImageSubscription::Start | ( | ) | [inline, virtual] |
overwrite to start up the data reading, is called at least once after creation
Start
Implements cop::Sensor.
Definition at line 96 of file ImageSubscription.h.
bool cop::ImageSubscription::Stop | ( | ) | [inline, virtual] |
overwrite to stop call this in the destructor if necessary, will be used to shut down cameras
Start
Reimplemented from cop::Sensor.
Definition at line 109 of file ImageSubscription.h.
sensor_msgs::CvBridge* cop::ImageSubscription::m_bridge [private] |
Definition at line 160 of file ImageSubscription.h.
bool cop::ImageSubscription::m_bWindowCreated [private] |
Definition at line 163 of file ImageSubscription.h.
Calibration
Definition at line 140 of file ImageSubscription.h.
bool cop::ImageSubscription::m_grabbing [private] |
Definition at line 164 of file ImageSubscription.h.
Definition at line 162 of file ImageSubscription.h.
unsigned int cop::ImageSubscription::m_max_cameraImagesStored [private] |
Definition at line 161 of file ImageSubscription.h.
std::string cop::ImageSubscription::m_stTopicName [private] |
Definition at line 159 of file ImageSubscription.h.