Skip to content

Commit

Permalink
Merge pull request #56 from FraunhoferIOSB/enhance/46_assertion
Browse files Browse the repository at this point in the history
enhance: Improved assertions and error messages
  • Loading branch information
boitumeloruf authored Dec 10, 2024
2 parents 4e350bf + 9c02cb5 commit a605c3e
Show file tree
Hide file tree
Showing 8 changed files with 59 additions and 69 deletions.
18 changes: 7 additions & 11 deletions camera_aravis2/include/camera_aravis2/camera_aravis_node_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@
#define CAMERA_ARAVIS2__CAMERA_ARAVIS_NODE_BASE_H_

// Std
#include <cassert>
#include <map>
#include <string>
#include <utility>
Expand All @@ -48,17 +49,12 @@ extern "C"
#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; \
#define CHECK_SUCCESS(expr, logger) \
if (!expr) \
{ \
RCLCPP_FATAL(logger, "%s:%i: Assertion on success of '%s' failed.", \
__FILE__, __LINE__, #expr); \
return; \
}

namespace camera_aravis2
Expand Down
42 changes: 16 additions & 26 deletions camera_aravis2/include/camera_aravis2/error.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,39 +38,27 @@
// ROS
#include <rclcpp/rclcpp.hpp>

/// Macro to assert success and log GError if necessary
#define ASSERT_GERROR(err, logger, success) \
if (err) \
{ \
success &= false; \
err.log(logger); \
} \
else \
{ \
success &= true; \
}

/// Macro to assert success and log GError if necessary with custommesage
#define ASSERT_GERROR_MSG(err, logger, custom_msg, success) \
if (err) \
{ \
success &= false; \
err.log(logger, custom_msg); \
} \
else \
{ \
success &= true; \
}

/// Macro to check if error occurred and log if necessary
#define CHECK_GERROR(err, logger) \
if (err) \
err.log(logger);
err.log(logger, __FILE__, __LINE__);

/// Macro to check if error occurred and log if necessary with costom message
#define CHECK_GERROR_MSG(err, logger, custom_msg) \
if (err) \
err.log(logger, custom_msg);
err.log(logger, __FILE__, __LINE__, custom_msg);

/// Macro to assert success and log GError if necessary
#define CHECK_SUCCESS_GERROR(err, logger, success) \
if (err) \
err.log(logger, __FILE__, __LINE__); \
success &= !err;

/// Macro to assert success and log GError if necessary with custom mesage
#define CHECK_SUCCESS_GERROR_MSG(err, logger, custom_msg, success) \
if (err) \
err.log(logger, __FILE__, __LINE__, custom_msg); \
success &= !err;

namespace camera_aravis2
{
Expand All @@ -92,6 +80,8 @@ class GuardedGError
operator bool() const;

void log(const rclcpp::Logger& logger,
const std::string& file,
const int& line,
const std::string& custom_msg = "") const;

//--- MEMBER DECLARATION ---//
Expand Down
22 changes: 11 additions & 11 deletions camera_aravis2/src/camera_aravis_node_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -263,8 +263,8 @@ bool CameraAravisNodeBase::getFeatureValue(const std::string& feature_name, T& v
typeid(T).name());
}

ASSERT_GERROR_MSG(err, logger_,
"In getting value for feature '" + feature_name + "'.", is_successful);
CHECK_SUCCESS_GERROR_MSG(err, logger_,
"In getting value for feature '" + feature_name + "'.", is_successful);

return is_successful;
}
Expand Down Expand Up @@ -293,7 +293,7 @@ bool CameraAravisNodeBase::setFeatureValue(const std::string& feature_name, cons
{
RCLCPP_WARN(logger_, "Feature '%s' is not available. Value will not be set.",
feature_name.c_str());
ASSERT_GERROR(err, logger_, is_successful);
CHECK_SUCCESS_GERROR(err, logger_, is_successful);
return false;
}

Expand Down Expand Up @@ -331,8 +331,8 @@ bool CameraAravisNodeBase::setFeatureValue(const std::string& feature_name, cons
typeid(T).name());
}

ASSERT_GERROR_MSG(err, logger_,
"In setting value for feature '" + feature_name + "'.", is_successful);
CHECK_SUCCESS_GERROR_MSG(err, logger_,
"In setting value for feature '" + feature_name + "'.", is_successful);

return is_successful;
}
Expand Down Expand Up @@ -384,7 +384,7 @@ bool CameraAravisNodeBase::setBoundedFeatureValue(const std::string& feature_nam
{
RCLCPP_WARN(logger_, "Feature '%s' is not available. Value will not be set.",
feature_name.c_str());
ASSERT_GERROR(err, logger_, is_successful);
CHECK_SUCCESS_GERROR(err, logger_, is_successful);
return false;
}

Expand All @@ -403,8 +403,8 @@ bool CameraAravisNodeBase::setBoundedFeatureValue(const std::string& feature_nam
typeid(T).name());
}

ASSERT_GERROR_MSG(err, logger_,
"In setting value for feature '" + feature_name + "'.", is_successful);
CHECK_SUCCESS_GERROR_MSG(err, logger_,
"In setting value for feature '" + feature_name + "'.", is_successful);

if (!is_successful)
return false;
Expand Down Expand Up @@ -667,14 +667,14 @@ bool CameraAravisNodeBase::executeCommand(const std::string& feature_name) const
{
RCLCPP_WARN(logger_, "Command '%s' is not available. Value will not be executed.",
feature_name.c_str());
ASSERT_GERROR(err, logger_, is_successful);
CHECK_SUCCESS_GERROR(err, logger_, is_successful);
return false;
}

arv_device_execute_command(p_device_, feature_name.c_str(), err.ref());

ASSERT_GERROR_MSG(err, logger_,
"In executing command '" + feature_name + "'.", is_successful);
CHECK_SUCCESS_GERROR_MSG(err, logger_,
"In executing command '" + feature_name + "'.", is_successful);

return is_successful;
}
Expand Down
6 changes: 3 additions & 3 deletions camera_aravis2/src/camera_driver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -445,7 +445,7 @@ bool CameraDriver::setupCameraStreamStructs()
//--- get bits per pixel
sensor.n_bits_pixel =
ARV_PIXEL_FORMAT_BIT_PER_PIXEL(arv_camera_get_pixel_format(p_camera_, err.ref()));
ASSERT_GERROR_MSG(err, logger_, "In getting 'Bits per Pixel'.", is_successful);
CHECK_SUCCESS_GERROR_MSG(err, logger_, "In getting 'Bits per Pixel'.", is_successful);

//--- get sensor size
RCLCPP_DEBUG(logger_, "Evaluating 'ImageFormatControl.SensorWidth' and "
Expand Down Expand Up @@ -1472,7 +1472,7 @@ void CameraDriver::publishCameraDiagnosticsLoop(double rate) const
GuardedGError err;
bool is_feature_available =
arv_device_is_feature_available(p_device_, name.c_str(), err.ref());
ASSERT_GERROR(err, logger_, is_successful)
CHECK_SUCCESS_GERROR(err, logger_, is_successful)

return (is_feature_available && is_successful);
};
Expand Down Expand Up @@ -1666,7 +1666,7 @@ void CameraDriver::spawnCameraStreams()
{
RCLCPP_FATAL(logger_, "Failed to open streams for camera %s.",
guid_.c_str());
ASSERT_SUCCESS(false);
return;
}

//--- Connect signals with callbacks and activate emission of signals
Expand Down
16 changes: 8 additions & 8 deletions camera_aravis2/src/camera_driver_gv.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ CameraDriverGv::CameraDriverGv(const rclcpp::NodeOptions& options) :
parameter_overrides_ = this->get_node_parameters_interface()->get_parameter_overrides();

//--- open camera device
ASSERT_SUCCESS(discoverAndOpenCameraDevice());
CHECK_SUCCESS(discoverAndOpenCameraDevice(), logger_);

//--- check if GEV Device.
if (!arv_camera_is_gv_device(p_camera_))
Expand All @@ -68,28 +68,28 @@ CameraDriverGv::CameraDriverGv(const rclcpp::NodeOptions& options) :
}

//--- set up structs holding relevant information of camera streams
ASSERT_SUCCESS(setupCameraStreamStructs());
CHECK_SUCCESS(setupCameraStreamStructs(), logger_);

//--- set device control settings
ASSERT_SUCCESS(setDeviceControlSettings());
CHECK_SUCCESS(setDeviceControlSettings(), logger_);

//--- set transport layer control settings
p_gv_tl_control_ = std::make_shared<GvTransportLayerControl>();
p_tl_control_ = std::dynamic_pointer_cast<GenTransportLayerControl>(p_gv_tl_control_);

ASSERT_SUCCESS(setTransportLayerControlSettings());
CHECK_SUCCESS(setTransportLayerControlSettings(), logger_);

//--- set image format control settings
ASSERT_SUCCESS(setImageFormatControlSettings());
CHECK_SUCCESS(setImageFormatControlSettings(), logger_);

//--- set acquisition control settings
ASSERT_SUCCESS(setAcquisitionControlSettings());
CHECK_SUCCESS(setAcquisitionControlSettings(), logger_);

//--- set analog control settings
ASSERT_SUCCESS(setAnalogControlSettings());
CHECK_SUCCESS(setAnalogControlSettings(), logger_);

//--- initialize services
ASSERT_SUCCESS(initializeServices());
CHECK_SUCCESS(initializeServices(), logger_);

//--- load dynamic parameters
setupDynamicParameters();
Expand Down
14 changes: 7 additions & 7 deletions camera_aravis2/src/camera_driver_uv.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ CameraDriverUv::CameraDriverUv(const rclcpp::NodeOptions& options) :
parameter_overrides_ = this->get_node_parameters_interface()->get_parameter_overrides();

//--- open camera device
ASSERT_SUCCESS(discoverAndOpenCameraDevice());
CHECK_SUCCESS(discoverAndOpenCameraDevice(), logger_);

//--- check if UV Device.
if (!arv_camera_is_uv_device(p_camera_))
Expand All @@ -66,26 +66,26 @@ CameraDriverUv::CameraDriverUv(const rclcpp::NodeOptions& options) :
}

//--- set up structs holding relevant information of camera streams
ASSERT_SUCCESS(setupCameraStreamStructs());
CHECK_SUCCESS(setupCameraStreamStructs(), logger_);

//--- set device control settings
ASSERT_SUCCESS(setDeviceControlSettings());
CHECK_SUCCESS(setDeviceControlSettings(), logger_);

//--- set transport layer control settings
p_uv_tl_control_ = std::make_shared<UvTransportLayerControl>();
p_tl_control_ = std::dynamic_pointer_cast<GenTransportLayerControl>(p_uv_tl_control_);

//--- set image format control settings
ASSERT_SUCCESS(setImageFormatControlSettings());
CHECK_SUCCESS(setImageFormatControlSettings(), logger_);

//--- set acquisition control settings
ASSERT_SUCCESS(setAcquisitionControlSettings());
CHECK_SUCCESS(setAcquisitionControlSettings(), logger_);

//--- set analog control settings
ASSERT_SUCCESS(setAnalogControlSettings());
CHECK_SUCCESS(setAnalogControlSettings(), logger_);

//--- initialize services
ASSERT_SUCCESS(initializeServices());
CHECK_SUCCESS(initializeServices(), logger_);

//--- load dynamic parameters
setupDynamicParameters();
Expand Down
2 changes: 1 addition & 1 deletion camera_aravis2/src/camera_xml_exporter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ CameraXmlExporter::CameraXmlExporter(const rclcpp::NodeOptions& options) :
setupParameters();

//--- open camera device
ASSERT_SUCCESS(discoverAndOpenCameraDevice());
CHECK_SUCCESS(discoverAndOpenCameraDevice(), logger_);

std::string camera_guid_str = CameraAravisNodeBase::constructCameraGuidStr(p_camera_);
RCLCPP_INFO(logger_, "Successfully Opened: %s", camera_guid_str.c_str());
Expand Down
8 changes: 6 additions & 2 deletions camera_aravis2/src/error.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,13 +68,17 @@ GuardedGError::operator bool() const

//==================================================================================================
void GuardedGError::log(const rclcpp::Logger& logger,
const std::string& file,
const int& line,
const std::string& custom_msg) const
{
if (err == nullptr)
return;

RCLCPP_ERROR(logger, "[%s] Code %i: %s. %s",
g_quark_to_string(err->domain), err->code, err->message, custom_msg.c_str());
RCLCPP_ERROR(logger, "%s:%i: %s (Code %i): %s. %s",
file.c_str(), line,
g_quark_to_string(err->domain),
err->code, err->message, custom_msg.c_str());
}

} // namespace camera_aravis2

0 comments on commit a605c3e

Please sign in to comment.