Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Added service to set WhiteBalanceAuto mode to Once #38

Merged
merged 1 commit into from
Sep 30, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,7 @@ add_service_files(
get_float_feature_value.srv
get_integer_feature_value.srv
get_string_feature_value.srv
one_shot_white_balance.srv
set_boolean_feature_value.srv
set_float_feature_value.srv
set_integer_feature_value.srv
Expand Down
4 changes: 4 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -146,6 +146,10 @@ specified in 'wb_ratio_selectors'. This list should be the same size as the rati
- Default: ```""```
- Example: ```"1.4,2.5"```

To trigger an automatic white balance computation and a subsequent setting of ```BalanceWhiteAuto``` to ```Once```, camera_aravis provides a service called ```trigger_one_shot_white_balance```.
Calling this service will trigger a one shot computation of the white balance parameters and return the newly computed balance ratio.
This can be called no matter which mode has been set previously.

### Activating PTP Timestamp

Some cameras support the use of the Precision Time Protocol (PTP) to set the timestamps of the
Expand Down
4 changes: 4 additions & 0 deletions include/camera_aravis/camera_aravis_nodelet.h
Original file line number Diff line number Diff line change
Expand Up @@ -74,6 +74,7 @@ extern "C" {
#include <camera_aravis/set_string_feature_value.h>
#include <camera_aravis/get_boolean_feature_value.h>
#include <camera_aravis/set_boolean_feature_value.h>
#include <camera_aravis/one_shot_white_balance.h>

#include <camera_aravis/camera_buffer_pool.h>
#include <camera_aravis/conversion_utils.h>
Expand Down Expand Up @@ -171,6 +172,9 @@ class CameraAravisNodelet : public nodelet::Nodelet
ros::ServiceServer set_boolean_service_;
bool setBooleanFeatureCallback(camera_aravis::set_boolean_feature_value::Request& request, camera_aravis::set_boolean_feature_value::Response& response);

ros::ServiceServer one_shot_white_balance_service_;
bool oneShotWhiteBalanceCallback(camera_aravis::one_shot_white_balance::Request& request, camera_aravis::one_shot_white_balance::Response& response);

// triggers a shot at regular intervals, sleeps in between
void softwareTriggerLoop();

Expand Down
55 changes: 55 additions & 0 deletions src/camera_aravis_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -677,6 +677,8 @@ void CameraAravisNodelet::spawnStream()
this->set_string_service_ = pnh.advertiseService("set_string_feature_value", &CameraAravisNodelet::setStringFeatureCallback, this);
this->set_boolean_service_ = pnh.advertiseService("set_boolean_feature_value", &CameraAravisNodelet::setBooleanFeatureCallback, this);

this->one_shot_white_balance_service_ = pnh.advertiseService("trigger_one_shot_white_balance", &CameraAravisNodelet::oneShotWhiteBalanceCallback, this);

ROS_INFO("Done initializing camera_aravis.");
}

Expand Down Expand Up @@ -772,6 +774,59 @@ bool CameraAravisNodelet::setBooleanFeatureCallback(camera_aravis::set_boolean_f
return true;
}

bool CameraAravisNodelet::oneShotWhiteBalanceCallback(camera_aravis::one_shot_white_balance::Request& request, camera_aravis::one_shot_white_balance::Response& response)
{
//--- set return values to default
response.is_successful = false;
response.balance_ratio_red = 0.f;
response.balance_ratio_green = 0.f;
response.balance_ratio_blue = 0.f;

//--- check for correct state of camera
if(!this->p_device_ || !implemented_features_["BalanceWhiteAuto"])
return false;

arv_device_set_string_feature_value(p_device_, "BalanceWhiteAuto", "Once");
if (arv_device_get_status(this->p_device_) == ARV_DEVICE_STATUS_SUCCESS)
{
const char* tmpCharPtr = arv_device_get_string_feature_value(p_device_, "BalanceWhiteAuto");
std::string modeStr = "n/a";
if(tmpCharPtr)
modeStr = std::string(tmpCharPtr);

if (implemented_features_["BalanceRatio"] && implemented_features_["BalanceRatioSelector"])
{
arv_device_set_string_feature_value(p_device_, "BalanceRatioSelector", "Red");
response.balance_ratio_red = static_cast<float>(
arv_device_get_float_feature_value(p_device_, "BalanceRatio"));

arv_device_set_string_feature_value(p_device_, "BalanceRatioSelector", "Green");
response.balance_ratio_green = static_cast<float>(
arv_device_get_float_feature_value(p_device_, "BalanceRatio"));

arv_device_set_string_feature_value(p_device_, "BalanceRatioSelector", "Blue");
response.balance_ratio_blue = static_cast<float>(
arv_device_get_float_feature_value(p_device_, "BalanceRatio"));
}

ROS_INFO("Setting Auto White Balance successful!");
ROS_INFO("> BalanceWhiteAuto Mode: %s", modeStr.c_str());
ROS_INFO("> BalanceRatio Red: %f", response.balance_ratio_red);
ROS_INFO("> BalanceRatio Green: %f", response.balance_ratio_green);
ROS_INFO("> BalanceRatio Blue: %f", response.balance_ratio_blue);


response.is_successful = true;
return true;
}
else
{
ROS_ERROR("Trying to set Auto White Balance once failed!");

return false;
}
}

void CameraAravisNodelet::resetPtpClock()
{
if (ptp_status_feature_.empty() || ptp_enable_feature_.empty())
Expand Down
5 changes: 5 additions & 0 deletions srv/one_shot_white_balance.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
---
bool is_successful
float32 balance_ratio_red
float32 balance_ratio_green
float32 balance_ratio_blue
Loading