Go to the documentation of this file.
33 #ifndef AVT_VIMBA_API_H
34 #define AVT_VIMBA_API_H
39 #include <sensor_msgs/Image.h>
46 using AVT::VmbAPI::CameraPtr;
47 using AVT::VmbAPI::FramePtr;
64 ROS_INFO_STREAM(
"[Vimba System]: AVT Vimba System initialized successfully");
81 std::map<VmbErrorType, std::string> error_msg;
102 std::map<VmbErrorType, std::string>::const_iterator iter = error_msg.find(error);
103 if (error_msg.end() != iter)
107 return "Unsupported error code passed.";
112 switch (interfaceType)
131 return "Read and write access";
133 return "Only read access";
135 return "Device configuration access";
137 return "Device read/write access without feature access (only addresses)";
141 return "Undefined access";
144 bool frameToImage(
const FramePtr vimba_frame_ptr, sensor_msgs::Image& image)
149 vimba_frame_ptr->GetWidth(width);
150 vimba_frame_ptr->GetHeight(height);
151 vimba_frame_ptr->GetPixelFormat(pixel_format);
152 vimba_frame_ptr->GetImageSize(nSize);
157 std::string encoding;
223 ROS_WARN(
"Received frame with unsupported pixel format %d", pixel_format);
228 VmbErrorType err = vimba_frame_ptr->GetImage(buffer_ptr);
247 ROS_INFO(
"Searching for cameras ...");
253 for (
const auto& camera : cameras)
257 std::string strModelname;
258 std::string strSerialNumber;
259 std::string strInterfaceID;
269 err = camera->GetName(strName);
275 err = camera->GetModel(strModelname);
278 ROS_ERROR_STREAM(
"[Could not get camera mode name. Error code: " << err <<
"]");
281 err = camera->GetSerialNumber(strSerialNumber);
284 ROS_ERROR_STREAM(
"[Could not get camera serial number. Error code: " << err <<
"]");
287 err = camera->GetInterfaceID(strInterfaceID);
290 ROS_ERROR_STREAM(
"[Could not get interface ID. Error code: " << err <<
"]");
293 err = camera->GetInterfaceType(interfaceType);
296 ROS_ERROR_STREAM(
"[Could not get interface type. Error code: " << err <<
"]");
299 err = camera->GetPermittedAccess(accessType);
316 ROS_WARN(
"Could not get cameras from Vimba System");
321 ROS_WARN(
"Could not start Vimba System");
const std::string BAYER_RGGB8
@ VmbPixelFormatBayerGR16
std::vector< CameraPtr > CameraPtrVector
#define ROS_ERROR_STREAM(args)
const std::string BAYER_GBRG8
void listAvailableCameras()
@ VmbPixelFormatBayerRG12
@ VmbPixelFormatBayerGB12
IMEXPORT VmbErrorType Startup()
static bool fillImage(Image &image, const std::string &encoding_arg, uint32_t rows_arg, uint32_t cols_arg, uint32_t step_arg, const void *data_arg)
@ VmbPixelFormatBayerGR10
@ VmbPixelFormatBayerGB12Packed
VmbErrorType GetCameras(CameraPtrVector &cameras)
@ VmbPixelFormatBayerRG10
std::string accessModeToString(VmbAccessModeType modeType)
@ VmbPixelFormatBayerBG10
@ VmbPixelFormatBayerRG16
@ VmbPixelFormatBayerGB16
const std::string BAYER_BGGR8
@ VmbPixelFormatBayerBG16
@ VmbPixelFormatBayerGB10
#define ROS_INFO_STREAM(args)
const std::string TYPE_32SC4
@ VmbPixelFormatBayerGR12
const ROSCPP_DECL std::string & getName()
@ VmbPixelFormatMono12Packed
bool frameToImage(const FramePtr vimba_frame_ptr, sensor_msgs::Image &image)
@ VmbPixelFormatBayerGR12Packed
std::string interfaceToString(VmbInterfaceType interfaceType)
const std::string TYPE_16SC1
const std::string TYPE_16UC3
@ VmbPixelFormatBayerBG12Packed
const std::string BAYER_GRBG8
@ VmbPixelFormatBayerRG12Packed
std::string errorCodeToMessage(VmbErrorType error)
@ VmbPixelFormatBayerBG12
avt_vimba_camera
Author(s): Allied Vision Technologies, Miquel Massot
autogenerated on Sat Jun 3 2023 02:14:12