Skip to content

Commit

Permalink
Make CCM runtime adjustable
Browse files Browse the repository at this point in the history
  • Loading branch information
treideme committed Sep 12, 2023
1 parent 0768e21 commit 40408e2
Showing 1 changed file with 9 additions and 6 deletions.
15 changes: 9 additions & 6 deletions src/bottlenose_camera_driver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -206,7 +206,7 @@ bool CameraDriver::update_runtime_parameters() {
m_camera_parameter_cache[param] = val;
RCLCPP_DEBUG_STREAM(get_logger(), "Set parameter " << param << " to " << val);
}
return true;
return set_ccm_profile();
}

bool CameraDriver::set_interval() {
Expand Down Expand Up @@ -273,6 +273,13 @@ bool CameraDriver::set_format() {

bool CameraDriver::set_ccm_profile() {
auto ccm_profile_str = get_parameter("CCMColorProfile").as_string();
try {
auto value = m_camera_parameter_cache.at("CCMColorProfile");
if(get<string>(value) == ccm_profile_str) {
return true;
}
} catch(std::out_of_range &e) { }

PvGenEnum *colorProfile = dynamic_cast<PvGenEnum *>( m_device->GetParameters()->Get("CCMColorProfile"));
int64_t num_entries = 0;
PvResult res = colorProfile->GetEntriesCount(num_entries);
Expand Down Expand Up @@ -300,6 +307,7 @@ bool CameraDriver::set_ccm_profile() {
return false;
}
RCLCPP_DEBUG_STREAM(get_logger(), "Set sensor color profile to " << str.GetAscii());
m_camera_parameter_cache["CCMColorProfile"] = ccm_profile_str;
return true;
}
}
Expand Down Expand Up @@ -463,11 +471,6 @@ void CameraDriver::management_thread() {
done = true;
return;
}
if(!set_ccm_profile()) {
disconnect();
done = true;
return;
}
if(!set_stereo()) {
disconnect();
done = true;
Expand Down

0 comments on commit 40408e2

Please sign in to comment.