Program Listing for File config_structs.h
↰ Return to documentation for file (include/camera_aravis2/config_structs.h
)
// Copyright (c) 2024 Fraunhofer IOSB and contributors
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
//
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
//
// * Neither the name of the Fraunhofer IOSB nor the names of its
// contributors may be used to endorse or promote products derived from
// this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.
#ifndef CAMERA_ARAVIS2__CONFIG_STRUCTS_H_
#define CAMERA_ARAVIS2__CONFIG_STRUCTS_H_
// Std
#include <cfloat>
#include <string>
#include <tuple>
#include <vector>
namespace camera_aravis2
{
struct TransportLayerControl
{
int64_t packet_size = 0;
int64_t inter_packet_delay = 0;
bool is_ptp_enable = false;
std::string ptp_status = "n/a";
// Offset from the PTP master clock in nanoseconds.
int64_t ptp_offset = 0;
};
struct Sensor
{
std::string frame_id = "";
int32_t width = 0;
int32_t height = 0;
std::string pixel_format = "n/a";
size_t n_bits_pixel = 0;
bool reverse_x = false;
bool reverse_y = false;
int binning_x = 1;
std::string binning_mode_x = "n/a";
int binning_y = 1;
std::string binning_mode_y = "n/a";
};
struct ImageRoi
{
int x = 0;
int y = 0;
int width = 0;
int width_min = 0;
int width_max = INT32_MAX;
int height = 0;
int height_min = 0;
int height_max = INT32_MAX;
};
struct AcquisitionControl
{
std::string acquisition_mode = "n/a";
int frame_count = 0;
std::string exposure_mode = "n/a";
std::string exposure_auto = "n/a";
double exposure_time = 0;
bool is_frame_rate_enable = true;
double frame_rate = 0.0;
double frame_rate_min = 0.0;
double frame_rate_max = DBL_MAX;
};
struct AnalogControl
{
std::string gain_auto = "n/a";
std::vector<std::tuple<std::string, float, float, float>> gain;
std::string black_level_auto = "n/a";
std::vector<std::tuple<std::string, float, float, float>> black_level;
std::string balance_white_auto = "n/a";
std::vector<std::tuple<std::string, float, float, float>> balance_ratio;
};
} // namespace camera_aravis2
#endif // CAMERA_ARAVIS2__CONFIG_STRUCTS_H_