Skip to content

Commit

Permalink
Merge pull request #8 from apl-ocean-engineering/devel/crrel_code_cle…
Browse files Browse the repository at this point in the history
…anup

Code cleanup during idle time at CRREL
  • Loading branch information
amarburg authored May 1, 2024
2 parents a5aac1d + 6165bb6 commit 100d6f8
Show file tree
Hide file tree
Showing 5 changed files with 112 additions and 379 deletions.
1 change: 1 addition & 0 deletions .docker/docker-compose.yml
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@ services:
stdin_open: true
tty: true
network_mode: host
command: /bin/bash
volumes:
- type: bind
source: ..
Expand Down
40 changes: 10 additions & 30 deletions arena_camera/include/arena_camera/arena_camera_nodelet.h
Original file line number Diff line number Diff line change
Expand Up @@ -88,13 +88,6 @@ class ArenaCameraNodeletBase : public nodelet::Nodelet {
*/
void onInit() override;

/// Getter for the current frame rate
/// @return the desired frame rate.
///
const double &frameRate() const {
return arena_camera_parameter_set_.frameRate();
}

/// Getter for the tf frame.
/// @return the camera frame.
///
Expand Down Expand Up @@ -133,18 +126,21 @@ class ArenaCameraNodeletBase : public nodelet::Nodelet {

// === Functions to get/set Frame Rate ===

void updateFrameRate();
float currentFrameRate();
void updateFrameRate(float frame_rate);

//==== Functions to get/set exposure ====

enum class AutoExposureMode : int { Off = 0, Once = 1, Continuous = 2 };

// Update exposure based on arena_camera_parameter_set
//
// If exp_mode == Off, exposure_ms is the **fixed exposure** set in the
// camera If exp_mode == Once or Continuous, exposure_ms is the **max
// exposure** allowed
// for the auto-exposure algorithm
/// Update exposure based on arena_camera_parameter_set
///
/// If exp_mode == Off, exposure_ms is the **fixed exposure** set in the
/// camera
///
/// If exp_mode == Once or Continuous, exposure_ms is the **max
/// exposure** allowed
/// for the auto-exposure algorithm
void setExposure(AutoExposureMode exp_mode, float exposure_ms);

void setAutoExposureGain(float exposure_damping);
Expand Down Expand Up @@ -186,7 +182,6 @@ class ArenaCameraNodeletBase : public nodelet::Nodelet {
float currentGamma();

//===== Functions for querying HDR channels (IMX490 only)

float currentHdrGain(int channel);
float currentHdrExposure(int channel);

Expand Down Expand Up @@ -223,21 +218,7 @@ class ArenaCameraNodeletBase : public nodelet::Nodelet {

/**
* Sets the target brightness which is the intensity-mean over all pixels.
* If the target exposure time is not in the range of Arena's auto target
* brightness range the extended brightness search is started.
* The Auto function of the Arena-API supports values from [50 - 205].
* Using a binary search, this range will be extended up to [1 - 255].
* @param target_brightness is the desired brightness. Range is [1...255].
* @param current_brightness is the current brightness with the given
* settings.
* @param exposure_auto flag which indicates if the target_brightness
* should be reached adapting the exposure time
* @param gain_auto flag which indicates if the target_brightness should be
* reached adapting the gain.
* @return true if the brightness could be reached or false otherwise.
*/
// bool setBrightness(const int &target_brightness, int &reached_brightness,
// const bool &exposure_auto, const bool &gain_auto);

void setTargetBrightness(unsigned int brightness);

Expand All @@ -262,7 +243,6 @@ class ArenaCameraNodeletBase : public nodelet::Nodelet {
size_t &reached_binning_x);
bool setBinningYValue(const size_t &target_binning_y,
size_t &reached_binning_y);
void disableAllRunningAutoBrightessFunctions();

ros::Publisher metadata_pub_, hdr_metadata_pub_;

Expand Down
101 changes: 2 additions & 99 deletions arena_camera/include/arena_camera/arena_camera_parameter.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
*
* Copyright (C) 2023 University of Washington. All rights reserved.
*
* based on, with original license that follows
* based on original license that follows
*
* Copyright (C) 2016, Magazino GmbH. All rights reserved.
*
Expand Down Expand Up @@ -70,8 +70,6 @@ class ArenaCameraParameter {
/// Getter for the serial number param
const std::string &serialNumber() const { return serial_number_; }

int mtuSize() const { return mtu_size_; }

/**
* Getter for the string describing the shutter mode
*/
Expand All @@ -80,19 +78,9 @@ class ArenaCameraParameter {
// Getter for the camera_frame_ set from ros-parameter server
const std::string &cameraFrame() const { return camera_frame_; }

// Getter for the frame_rate_ read from ros-parameter server
const double &frameRate() const { return frame_rate_; }

// Getter for the image_encoding_ read from ros-parameter server
const std::string &imageEncoding() const { return image_encoding_; }

/**
* Setter for the frame_rate_ initially set from ros-parameter server
* The frame rate needs to be updated with the value the camera supports
*/
// void setFrameRate(const ros::NodeHandle& nh, const double& frame_rate);
void setFrameRate(const double &frame_rate);

// Getter for the camera_info_url set from ros-parameter server
const std::string &cameraInfoURL() const { return camera_info_url_; }

Expand Down Expand Up @@ -131,88 +119,10 @@ class ArenaCameraParameter {
// #######################################################################
// ###################### Image Intensity Settings ######################
// #######################################################################
// The following settings do *NOT* have to be set. Each camera has default
// values which provide an automatic image adjustment
// If one would like to adjust image brightness, it is not
// #######################################################################

/**
* The target gain in percent of the maximal value the camera supports
* For USB-Cameras, the gain is in dB, for GigE-Cameras it is given in so
* called 'device specific units'.
*/
double gain_;

/**
* Flag which indicates if the gain value is provided and hence should be
* set during startup
*/
bool gain_given_;

/**
* Gamma correction of pixel intensity.
* Adjusts the brightness of the pixel values output by the camera's sensor
* to account for a non-linearity in the human perception of brightness or
* of the display system (such as CRT).
*/
double gamma_;

/**
* Flag which indicates if the gamma correction value is provided and
* hence should be set during startup
*/
bool gamma_given_;

/**
* The average intensity value of the images. It depends on the exposure
* time as well as the gain setting. If 'exposure' is provided, the
* interface will try to reach the desired brightness by only varying the
* gain. (What may often fail, because the range of possible exposure
* values is many times higher than the gain range).
* If 'gain' is provided, the interface will try to reach the desired
* brightness by only varying the exposure time. If gain AND exposure are
* given, it is not possible to reach the brightness, because both are
* assumed to be fix.
*/
int brightness_;

/**
* Flag which indicates if the average brightness is provided and hence
* should be set during startup
*/
bool brightness_given_;

/**
* Only relevant, if 'brightness' is set as ros-parameter:
* The brightness_continuous flag controls the auto brightness function.
* If it is set to false, the brightness will only be reached once.
* Hence changing light conditions lead to changing brightness values.
* If it is set to true, the given brightness will be reached continuously,
* trying to adapt to changing light conditions. This is only possible for
* values in the possible auto range of the arena API which is
* e.g. [50 - 205] for acA2500-14um and acA1920-40gm
*/
bool brightness_continuous_;

/**
* Only relevant, if 'brightness' is given as ros-parameter:
* If the camera should try to reach and / or keep the brightness, hence
* adapting to changing light conditions, at least one of the following
* flags must be set. If both are set, the interface will use the profile
* that tries to keep the gain at minimum to reduce white noise.
* The exposure_auto flag indicates, that the desired brightness will
* be reached by adapting the exposure time.
* The gain_auto flag indicates, that the desired brightness will be
* reached by adapting the gain.
*/
bool exposure_auto_;
bool gain_auto_;

bool enable_lut_;
// #######################################################################

double exposure_ms_;
double auto_exposure_max_ms_;
// #######################################################################

/**
* The MTU size. Only used for GigE cameras.
Expand Down Expand Up @@ -281,13 +191,6 @@ class ArenaCameraParameter {

std::string serial_number_;

/**
* The desired publisher frame rate if listening to the topics.
* This parameter can only be set once at startup
* Calling the GrabImages-Action can result in a higher framerate
*/
double frame_rate_;

/**
* The CameraInfo URL (Uniform Resource Locator) where the optional
* intrinsic camera calibration parameters are stored. This URL string will
Expand Down
Loading

0 comments on commit 100d6f8

Please sign in to comment.