|
24 | 24 | #include <memory>
|
25 | 25 | #include <nlohmann/json.hpp>
|
26 | 26 | #include <shisen_cpp/camera/node/camera_node.hpp>
|
| 27 | +#include <jitsuyo/config.hpp> |
27 | 28 |
|
28 | 29 | #include <fstream>
|
29 | 30 | #include <memory>
|
@@ -199,38 +200,38 @@ void CameraNode::configure_capture_setting(const CaptureSetting & capture_settin
|
199 | 200 |
|
200 | 201 | void CameraNode::load_configuration(const std::string & path)
|
201 | 202 | {
|
202 |
| - std::string ss = path + "capture_settings.json"; |
203 |
| - |
204 |
| - std::ifstream input(ss, std::ifstream::in); |
205 |
| - if (!input.is_open()) { |
206 |
| - throw std::runtime_error("Unable to open `" + ss + "`!"); |
| 203 | + nlohmann::json config; |
| 204 | + if (!jitsuyo::load_config(path, "capture_settings.json", config)) { |
| 205 | + throw std::runtime_error("Unable to open `" + path + "capture_settings.json`!"); |
207 | 206 | }
|
208 | 207 |
|
209 |
| - nlohmann::json config = nlohmann::json::parse(input); |
210 |
| - |
211 | 208 | CaptureSetting capture_setting;
|
212 | 209 |
|
213 |
| - // Get all config |
214 |
| - for (auto & item : config.items()) { |
215 |
| - try { |
216 |
| - if (item.key() == "brightness") { |
217 |
| - capture_setting.brightness.set(item.value()); |
218 |
| - } else if (item.key() == "contrast") { |
219 |
| - capture_setting.contrast.set(item.value()); |
220 |
| - } else if (item.key() == "saturation") { |
221 |
| - capture_setting.saturation.set(item.value()); |
222 |
| - } else if (item.key() == "temperature") { |
223 |
| - capture_setting.temperature.set(item.value()); |
224 |
| - } else if (item.key() == "exposure") { |
225 |
| - capture_setting.exposure.set(item.value()); |
226 |
| - } else if (item.key() == "gain") { |
227 |
| - capture_setting.gain.set(item.value()); |
228 |
| - } |
229 |
| - } catch (nlohmann::json::parse_error & ex) { |
230 |
| - throw std::runtime_error("Parse error at byte `" + std::to_string(ex.byte) + "`!"); |
231 |
| - } |
| 210 | + int setting_brightness; |
| 211 | + int setting_contrast; |
| 212 | + int setting_saturation; |
| 213 | + int setting_temperature; |
| 214 | + int setting_exposure; |
| 215 | + int setting_gain; |
| 216 | + |
| 217 | + if (!jitsuyo::assign_val(config, "brightness", setting_brightness) || |
| 218 | + !jitsuyo::assign_val(config, "contrast", setting_contrast) || |
| 219 | + !jitsuyo::assign_val(config, "saturation", setting_saturation) || |
| 220 | + !jitsuyo::assign_val(config, "temperature", setting_temperature) || |
| 221 | + !jitsuyo::assign_val(config, "exposure", setting_exposure) || |
| 222 | + !jitsuyo::assign_val(config, "gain", setting_gain)) |
| 223 | + { |
| 224 | + std::cout << "Error found at section `capture_settings`" << std::endl; |
| 225 | + throw std::runtime_error("Failed to load config file `" + path + "capture_settings.json`"); |
232 | 226 | }
|
233 | 227 |
|
| 228 | + capture_setting.brightness.set(setting_brightness); |
| 229 | + capture_setting.contrast.set(setting_contrast); |
| 230 | + capture_setting.saturation.set(setting_saturation); |
| 231 | + capture_setting.temperature.set(setting_temperature); |
| 232 | + capture_setting.exposure.set(setting_exposure); |
| 233 | + capture_setting.gain.set(setting_gain); |
| 234 | + |
234 | 235 | configure_capture_setting(capture_setting);
|
235 | 236 | }
|
236 | 237 |
|
|
0 commit comments