38 #include <avt_vimba_camera/AvtVimbaCameraConfig.h> 42 #include <dynamic_reconfigure/SensorLevels.h> 43 #include <sensor_msgs/Image.h> 44 #include <sensor_msgs/CameraInfo.h> 45 #include <sensor_msgs/SetCameraInfo.h> 48 #include <dynamic_reconfigure/server.h> 57 using AVT::VmbAPI::IFrameObserverPtr;
127 typedef dynamic_reconfigure::SensorLevels
Levels;
132 typedef avt_vimba_camera::AvtVimbaCameraConfig
Config;
158 template<
typename T>
bool getFeatureValue(
const std::string& feature_str, T& val);
159 bool getFeatureValue(
const std::string& feature_str, std::string& val);
160 template<
typename T>
bool setFeatureValue(
const std::string& feature_str,
const T& val);
161 bool runCommand(
const std::string& command_str);
175 void start(Config& config);
178 void pollCallback(polled_camera::GetPolledImage::Request& req,
179 polled_camera::GetPolledImage::Response& rsp,
180 sensor_msgs::Image& image,
181 sensor_msgs::CameraInfo& info);
188 void configure(Config& newconfig, uint32_t level);
void updateAcquisitionConfig(const Config &config, FeaturePtrVector feature_ptr_vec)
void configure(Config &newconfig, uint32_t level)
CameraPtr openCamera(std::string id)
NetPointer< Frame, AVT::VmbAPINET::Frame > FramePtr
void updatePixelFormatConfig(const Config &config, FeaturePtrVector feature_ptr_vec)
VmbInt64_t vimba_camera_max_width_
std::map< VmbErrorType, std::string > vimba_error_code_to_message_
dynamic_reconfigure::Server< Config > ReconfigureServer
void updateWhiteBalanceConfig(const Config &config, FeaturePtrVector feature_ptr_vec)
void pollCallback(polled_camera::GetPolledImage::Request &req, polled_camera::GetPolledImage::Response &rsp, sensor_msgs::Image &image, sensor_msgs::CameraInfo &info)
void updateIrisConfig(const Config &config, FeaturePtrVector feature_ptr_vec)
std::string trigger_source_
bool runCommand(const std::string &command_str)
VimbaSystem & vimba_system_
void updateGPIOConfig(const Config &config, FeaturePtrVector feature_ptr_vec)
void updateBandwidthConfig(const Config &config, FeaturePtrVector feature_ptr_vec)
ReconfigureServer reconfigure_server_
bool setFeatureValue(const std::string &feature_str, const T &val)
void updateROIConfig(Config &config, FeaturePtrVector feature_ptr_vec)
image_transport::ImageTransport it_
void frameCallback(const FramePtr vimba_frame_ptr)
FrameObserver * vimba_frame_observer_ptr_
dynamic_reconfigure::SensorLevels Levels
image_transport::CameraPublisher streaming_pub_
std::string errorCodeToMessage(VmbErrorType eErr)
VimbaROS(ros::NodeHandle nh, ros::NodeHandle nhp)
NetPointer< Camera, AVT::VmbAPINET::Camera > CameraPtr
bool getFeatureValue(const std::string &feature_str, T &val)
ros::Subscriber trigger_sub_
void printAllCameraFeatures(CameraPtr camera)
sensor_msgs::CameraInfo cam_info_
bool frameToImage(const FramePtr vimba_frame_ptr, sensor_msgs::Image &image)
void updateImageModeConfig(const Config &config, FeaturePtrVector feature_ptr_vec)
void updateExposureConfig(const Config &config, FeaturePtrVector feature_ptr_vec)
boost::shared_ptr< camera_info_manager::CameraInfoManager > cinfo_
polled_camera::PublicationServer poll_srv_
void updatePtpModeConfig(const Config &config, FeaturePtrVector feature_ptr_vec)
void listAvailableCameras(void)
std::vector< FeaturePtr > FeaturePtrVector
void start(Config &config)
std::string interfaceToString(VmbInterfaceType interfaceType)
FramePtr vimba_frame_ptr_
void updateCameraInfo(const Config &config)
CameraPtr vimba_camera_ptr_
std::string accessModeToString(VmbAccessModeType modeType)
int getTriggerModeInt(std::string mode)
avt_vimba_camera::AvtVimbaCameraConfig Config
VmbInt64_t vimba_camera_max_height_
void updateGainConfig(const Config &config, FeaturePtrVector feature_ptr_vec)