Program Listing for File camera_aravis_node_base.h
↰ Return to documentation for file (include/camera_aravis2/camera_aravis_node_base.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__CAMERA_ARAVIS_NODE_BASE_H_
#define CAMERA_ARAVIS2__CAMERA_ARAVIS_NODE_BASE_H_
// Std
#include <map>
#include <string>
#include <utility>
#include <vector>
// Aravis
extern "C"
{
#include "aravis-0.8/arv.h"
}
// ROS
#include <rclcpp/rclcpp.hpp>
// camera_aravis2
#include "camera_aravis2/error.h"
// Macro to assert success of given function
#define ASSERT_SUCCESS(fn) \
if (!fn) \
{ \
return; \
}
// Macro to assert success of given function and shut down if not successful
#define ASSERT_SUCCESS_AND_SHUTDOWN(fn) \
if (!fn) \
{ \
rclcpp::shutdown(); \
return; \
}
namespace camera_aravis2
{
class CameraAravisNodeBase : public rclcpp::Node
{
//--- METHOD DECLARATION ---//
public:
explicit CameraAravisNodeBase(const std::string& name,
const rclcpp::NodeOptions& options = rclcpp::NodeOptions());
virtual ~CameraAravisNodeBase();
bool isInitialized() const;
[[nodiscard]] bool listAvailableCameraDevices() const;
protected:
virtual void setUpParameters();
[[nodiscard]] bool discoverAndOpenCameraDevice();
[[nodiscard]] bool getNestedParameter(const std::string& parent_name,
const std::string& param_name,
rclcpp::ParameterValue& param_value) const;
[[nodiscard]] bool getNestedParameterList(
const std::string& parent_name,
const std::string& param_name,
std::vector<std::pair<std::string, rclcpp::ParameterValue>>& param_values) const;
template <typename T>
bool getFeatureValue(const std::string& feature_name, T& value) const;
template <typename T>
bool setFeatureValue(const std::string& feature_name, const T& value) const;
template <typename T>
bool setFeatureValue(const std::string& feature_name, const T& value,
const T& min, const T& max) const;
template <typename T>
bool setBoundedFeatureValue(const std::string& feature_name, const T& value,
T* min = nullptr, T* max = nullptr) const;
template <typename T>
bool setFeatureValueFromParameter(const std::string& feature_name,
const rclcpp::ParameterValue& parameter_value,
const uint& idx = 0) const;
template <typename T>
bool setFeatureValueFromParameter(const std::string& feature_name,
const rclcpp::ParameterValue& parameter_value,
const T& min, const T& max,
const uint& idx = 0) const;
bool setFeatureValuesFromParameterList(
const std::vector<std::pair<std::string, rclcpp::ParameterValue>>& param_values,
const uint& idx = 0) const;
template <typename T>
bool setBoundedFeatureValueFromParameter(const std::string& feature_name,
const rclcpp::ParameterValue& parameter_value,
T* min = nullptr, T* max = nullptr,
const uint& idx = 0) const;
template <typename T>
bool isParameterValueEqualTo(const rclcpp::ParameterValue& parameter_value,
const T& test_value,
const uint& idx = 0) const;
bool executeCommand(const std::string& feature_name) const;
//--- FUNCTION DECLARATION ---//
protected:
static std::string constructCameraGuidStr(ArvCamera* p_cam);
static void handleControlLostSignal(ArvDevice* p_device, gpointer p_user_data);
//--- MEMBER DECLARATION ---//
protected:
bool is_initialized_;
rclcpp::Logger logger_;
ArvDevice* p_device_;
ArvCamera* p_camera_;
std::string guid_;
std::map<std::string, rclcpp::ParameterValue> parameter_overrides_;
bool is_verbose_enable_;
};
} // namespace camera_aravis2
#endif // CAMERA_ARAVIS2__CAMERA_ARAVIS_NODE_BASE_H_