Public Member Functions |
int | getHeight () |
int | getMaxHeight () |
int | getMaxWidth () |
int | getWidth () |
| VimbaROS (ros::NodeHandle nh, ros::NodeHandle nhp) |
Private Types |
typedef
avt_vimba_camera::AvtVimbaCameraConfig | Config |
typedef driver_base::SensorLevels | Levels |
typedef
dynamic_reconfigure::Server
< Config > | ReconfigureServer |
Private Member Functions |
std::string | accessModeToString (VmbAccessModeType modeType) |
void | configure (Config &newconfig, uint32_t level) |
std::string | errorCodeToMessage (VmbErrorType eErr) |
void | frameCallback (const FramePtr vimba_frame_ptr) |
bool | frameToImage (const FramePtr vimba_frame_ptr, sensor_msgs::Image &image) |
template<typename T > |
bool | getFeatureValue (const std::string &feature_str, T &val) |
bool | getFeatureValue (const std::string &feature_str, std::string &val) |
int | getTriggerModeInt (std::string mode) |
void | initApi (void) |
std::string | interfaceToString (VmbInterfaceType interfaceType) |
void | listAvailableCameras (void) |
CameraPtr | openCamera (std::string id) |
void | pollCallback (polled_camera::GetPolledImage::Request &req, polled_camera::GetPolledImage::Response &rsp, sensor_msgs::Image &image, sensor_msgs::CameraInfo &info) |
void | printAllCameraFeatures (CameraPtr camera) |
bool | runCommand (const std::string &command_str) |
template<typename T > |
bool | setFeatureValue (const std::string &feature_str, const T &val) |
void | start (Config &config) |
void | stop () |
void | updateAcquisitionConfig (const Config &config, FeaturePtrVector feature_ptr_vec) |
void | updateBandwidthConfig (const Config &config, FeaturePtrVector feature_ptr_vec) |
void | updateCameraInfo (const Config &config) |
void | updateExposureConfig (const Config &config, FeaturePtrVector feature_ptr_vec) |
void | updateGainConfig (const Config &config, FeaturePtrVector feature_ptr_vec) |
void | updateGPIOConfig (const Config &config, FeaturePtrVector feature_ptr_vec) |
void | updateImageModeConfig (const Config &config, FeaturePtrVector feature_ptr_vec) |
void | updatePixelFormatConfig (const Config &config, FeaturePtrVector feature_ptr_vec) |
void | updatePtpModeConfig (const Config &config, FeaturePtrVector feature_ptr_vec) |
void | updateROIConfig (Config &config, FeaturePtrVector feature_ptr_vec) |
void | updateWhiteBalanceConfig (const Config &config, FeaturePtrVector feature_ptr_vec) |
Private Attributes |
sensor_msgs::CameraInfo | cam_info_ |
Config | camera_config_ |
boost::shared_ptr
< camera_info_manager::CameraInfoManager > | cinfo_ |
bool | first_run_ |
std::string | frame_id_ |
image_transport::ImageTransport | it_ |
ros::NodeHandle | nh_ |
ros::NodeHandle | nhp_ |
int | num_frames_ |
polled_camera::PublicationServer | poll_srv_ |
ReconfigureServer | reconfigure_server_ |
bool | running_ |
image_transport::CameraPublisher | streaming_pub_ |
std::string | trigger_source_ |
int | trigger_source_int_ |
ros::Subscriber | trigger_sub_ |
VmbInt64_t | vimba_camera_max_height_ |
VmbInt64_t | vimba_camera_max_width_ |
CameraPtr | vimba_camera_ptr_ |
std::map< VmbErrorType,
std::string > | vimba_error_code_to_message_ |
FrameObserver * | vimba_frame_observer_ptr_ |
FramePtr | vimba_frame_ptr_ |
VimbaSystem & | vimba_system_ |
Definition at line 95 of file vimba_ros.h.