Skip to content

Commit

Permalink
Update auto exposure/whitebalance param names
Browse files Browse the repository at this point in the history
Hardcoding them to match Stretch's cameras
until ros-drivers#260 is resolved
  • Loading branch information
nickswalker committed Aug 29, 2023
1 parent 7115c62 commit 5153146
Showing 1 changed file with 8 additions and 22 deletions.
30 changes: 8 additions & 22 deletions src/usb_cam_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -280,39 +280,25 @@ void UsbCamNode::set_v4l2_params()

// check auto white balance
if (m_parameters.auto_white_balance) {
m_camera->set_v4l_parameter("white_balance_temperature_auto", 1);
RCLCPP_INFO(this->get_logger(), "Setting 'white_balance_temperature_auto' to %d", 1);
m_camera->set_v4l_parameter("white_balance_automatic", 1);
RCLCPP_INFO(this->get_logger(), "Setting 'white_balance_automatic' to %d", 1);
} else {
RCLCPP_INFO(this->get_logger(), "Setting 'white_balance' to %d", m_parameters.white_balance);
m_camera->set_v4l_parameter("white_balance_temperature_auto", 0);
m_camera->set_v4l_parameter("white_balance_automatic", 0);
m_camera->set_v4l_parameter("white_balance_temperature", m_parameters.white_balance);
}

// check auto exposure
if (!m_parameters.autoexposure) {
RCLCPP_INFO(this->get_logger(), "Setting 'exposure_auto' to %d", 1);
RCLCPP_INFO(this->get_logger(), "Setting 'auto_exposure' to %d", 1);
RCLCPP_INFO(this->get_logger(), "Setting 'exposure' to %d", m_parameters.exposure);
// turn down exposure control (from max of 3)
m_camera->set_v4l_parameter("exposure_auto", 1);
m_camera->set_v4l_parameter("auto_exposure", 1);
// change the exposure level
m_camera->set_v4l_parameter("exposure_absolute", m_parameters.exposure);
m_camera->set_v4l_parameter("auto_exposure", m_parameters.exposure);
} else {
RCLCPP_INFO(this->get_logger(), "Setting 'exposure_auto' to %d", 3);
m_camera->set_v4l_parameter("exposure_auto", 3);
}

// check auto focus
if (m_parameters.autofocus) {
m_camera->set_auto_focus(1);
RCLCPP_INFO(this->get_logger(), "Setting 'focus_auto' to %d", 1);
m_camera->set_v4l_parameter("focus_auto", 1);
} else {
RCLCPP_INFO(this->get_logger(), "Setting 'focus_auto' to %d", 0);
m_camera->set_v4l_parameter("focus_auto", 0);
if (m_parameters.focus >= 0) {
RCLCPP_INFO(this->get_logger(), "Setting 'focus_absolute' to %d", m_parameters.focus);
m_camera->set_v4l_parameter("focus_absolute", m_parameters.focus);
}
RCLCPP_INFO(this->get_logger(), "Setting 'auto_exposure' to %d", 3);
m_camera->set_v4l_parameter("auto_exposure", 3);
}
}

Expand Down

0 comments on commit 5153146

Please sign in to comment.