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

[Enhancement] Set Camera Capture Size From Configuration #31

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
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 include/shisen_cpp/camera/provider/image_provider.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@ class ImageProvider
void set_image(const Image & image);
void set_mat(cv::Mat mat);
void update_mat();
void initialize_video_capture(const Options & options);

const Image & get_image() const;
cv::Mat get_mat() const;
Expand Down
11 changes: 10 additions & 1 deletion src/shisen_cpp/camera/node/camera_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -237,13 +237,17 @@ void CameraNode::load_configuration(const std::string & path)
int setting_temperature;
int setting_exposure;
int setting_gain;
int setting_width;
int setting_height;

if (!jitsuyo::assign_val(config, "brightness", setting_brightness) ||
!jitsuyo::assign_val(config, "contrast", setting_contrast) ||
!jitsuyo::assign_val(config, "saturation", setting_saturation) ||
!jitsuyo::assign_val(config, "temperature", setting_temperature) ||
!jitsuyo::assign_val(config, "exposure", setting_exposure) ||
!jitsuyo::assign_val(config, "gain", setting_gain))
!jitsuyo::assign_val(config, "gain", setting_gain) ||
!jitsuyo::assign_val(config, "width", setting_width) ||
!jitsuyo::assign_val(config, "height", setting_height))
{
std::cout << "Error found at section `capture_settings`" << std::endl;
throw std::runtime_error("Failed to load config file `" + path + "capture_settings.json`");
Expand All @@ -257,6 +261,11 @@ void CameraNode::load_configuration(const std::string & path)
capture_setting.gain.set(setting_gain);

configure_capture_setting(capture_setting);

options.width = setting_width;
options.height = setting_height;

image_provider->initialize_video_capture(options);
}

} // namespace shisen_cpp::camera
13 changes: 9 additions & 4 deletions src/shisen_cpp/camera/provider/image_provider.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,15 @@ ImageProvider::ImageProvider(const Options & options)
throw std::runtime_error("unable to open camera on `" + options.camera_file_name + "`");
}

initialize_video_capture(options);
}

ImageProvider::~ImageProvider()
{
}

void ImageProvider::initialize_video_capture(const Options & options)
{
video_capture->set(cv::CAP_PROP_FRAME_WIDTH, options.width);
video_capture->set(cv::CAP_PROP_FRAME_HEIGHT, options.height);
video_capture->set(cv::CAP_PROP_AUTOFOCUS, 0); // Disable autofocus
Expand All @@ -45,10 +54,6 @@ ImageProvider::ImageProvider(const Options & options)
video_capture->set(cv::CAP_PROP_FOCUS, 0); // Set focus to 0
}

ImageProvider::~ImageProvider()
{
}

void ImageProvider::set_image(const Image & image)
{
current_image_msg = image;
Expand Down
2 changes: 2 additions & 0 deletions src/shisen_cpp/config/grpc/call_data_get_capture_setting.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,8 @@ void CallDataGetCaptureSetting::HandleRequest()
RCLCPP_ERROR(rclcpp::get_logger("Get config"), "Failed to load config!");
return;
}
data.erase("width");
data.erase("height");
std::string capture_setting = data.dump();
try {
reply_.set_json_capture(capture_setting);
Expand Down
11 changes: 10 additions & 1 deletion src/shisen_cpp/config/grpc/call_data_save_capture_setting.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,8 +52,17 @@ void CallDataSaveCaptureSetting::HandleRequest()
std::replace(json_string.begin(), json_string.end(), '\\', ' ');
nlohmann::json capture_data = nlohmann::json::parse(json_string);

nlohmann::json data;
if (!jitsuyo::load_config(path_, "capture_settings.json", data)) {
RCLCPP_ERROR(rclcpp::get_logger("Get config"), "Failed to load config!");
return;
}

capture_data["width"] = data["width"];
capture_data["height"] = data["height"];

jitsuyo::save_config(path_, "capture_settings.json", capture_data);
RCLCPP_INFO(rclcpp::get_logger("Save config"), "config has been saved! ");
RCLCPP_INFO(rclcpp::get_logger("Save config"), "config has been saved!");
} catch (nlohmann::json::exception & e) {
RCLCPP_ERROR(rclcpp::get_logger("Save config"), e.what());
}
Expand Down
Loading