Skip to content

Commit 1a96543

Browse files
authored
Merge pull request #28 from ichiro-its/enhancement/use-jitsuyo-utils
[Sprint 22/23 | PD-421] - [Enhancement] Use Jitsuyo For Utilities
2 parents 0078196 + 4d6a9d2 commit 1a96543

10 files changed

+49
-140
lines changed

CMakeLists.txt

+3-1
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@ find_package(keisan REQUIRED)
2020
find_package(OpenCV REQUIRED)
2121
find_package(rclcpp REQUIRED)
2222
find_package(shisen_interfaces REQUIRED)
23+
find_package(jitsuyo REQUIRED)
2324
find_package(sensor_msgs REQUIRED)
2425
find_package(std_msgs REQUIRED)
2526
find_package(Protobuf CONFIG REQUIRED)
@@ -39,7 +40,6 @@ add_library(${PROJECT_NAME} SHARED
3940
"src/${PROJECT_NAME}/config/grpc/call_data_get_image.cpp"
4041
"src/${PROJECT_NAME}/config/grpc/call_data_save_capture_setting.cpp"
4142
"src/${PROJECT_NAME}/config/grpc/call_data_set_capture_setting.cpp"
42-
"src/${PROJECT_NAME}/config/utils/config.cpp"
4343
"src/${PROJECT_NAME}/utility/capture_setting.cpp"
4444
"src/${PROJECT_NAME}/utility/interface.cpp"
4545
"src/${PROJECT_NAME}/node/shisen_cpp_node.cpp"
@@ -72,6 +72,7 @@ ament_target_dependencies(${PROJECT_NAME}
7272
OpenCV
7373
rclcpp
7474
shisen_interfaces
75+
jitsuyo
7576
sensor_msgs
7677
cv_bridge
7778
std_msgs
@@ -82,6 +83,7 @@ ament_target_dependencies(${PROJECT_NAME}_exported
8283
OpenCV
8384
rclcpp
8485
shisen_interfaces
86+
jitsuyo
8587
sensor_msgs
8688
cv_bridge
8789
std_msgs)

include/shisen_cpp/config/utils/config.hpp

-44
This file was deleted.

include/shisen_cpp/node/shisen_cpp_node.hpp

-1
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,6 @@
2424
#include <rclcpp/rclcpp.hpp>
2525
#include <shisen_cpp/camera/node/camera_node.hpp>
2626
#include <shisen_cpp/config/grpc/config.hpp>
27-
#include <shisen_cpp/config/utils/config.hpp>
2827
#include <shisen_cpp/utility.hpp>
2928

3029
#include <memory>

package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,7 @@
88
<license>MIT License</license>
99
<buildtool_depend>ament_cmake</buildtool_depend>
1010
<depend>cv_bridge</depend>
11+
<depend>jitsuyo</depend>
1112
<depend>keisan</depend>
1213
<depend>libopencv-dev</depend>
1314
<depend>rclcpp</depend>

src/shisen_cpp/camera/node/camera_node.cpp

+27-26
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,7 @@
2424
#include <memory>
2525
#include <nlohmann/json.hpp>
2626
#include <shisen_cpp/camera/node/camera_node.hpp>
27+
#include <jitsuyo/config.hpp>
2728

2829
#include <fstream>
2930
#include <memory>
@@ -199,38 +200,38 @@ void CameraNode::configure_capture_setting(const CaptureSetting & capture_settin
199200

200201
void CameraNode::load_configuration(const std::string & path)
201202
{
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`!");
207206
}
208207

209-
nlohmann::json config = nlohmann::json::parse(input);
210-
211208
CaptureSetting capture_setting;
212209

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`");
232226
}
233227

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+
234235
configure_capture_setting(capture_setting);
235236
}
236237

src/shisen_cpp/config/grpc/call_data_get_capture_setting.cpp

+8-3
Original file line numberDiff line numberDiff line change
@@ -20,9 +20,9 @@
2020

2121
#include <rclcpp/rclcpp.hpp>
2222
#include <shisen_cpp/config/grpc/call_data_get_capture_setting.hpp>
23-
#include <shisen_cpp/config/utils/config.hpp>
2423
#include <shisen_interfaces/shisen.grpc.pb.h>
2524
#include <shisen_interfaces/shisen.pb.h>
25+
#include <jitsuyo/config.hpp>
2626

2727
namespace shisen_cpp
2828
{
@@ -46,9 +46,14 @@ void CallDataGetCaptureSetting::WaitForRequest()
4646

4747
void CallDataGetCaptureSetting::HandleRequest()
4848
{
49-
Config config(path_);
49+
nlohmann::json data;
50+
if (!jitsuyo::load_config(path_, "capture_settings.json", data)) {
51+
RCLCPP_ERROR(rclcpp::get_logger("Get config"), "Failed to load config!");
52+
return;
53+
}
54+
std::string capture_setting = data.dump();
5055
try {
51-
reply_.set_json_capture(config.get_capture_setting("capture"));
56+
reply_.set_json_capture(capture_setting);
5257
RCLCPP_INFO(rclcpp::get_logger("Get config"), "config has been sent!");
5358
} catch (nlohmann::json::exception & e) {
5459
RCLCPP_ERROR(rclcpp::get_logger("Publish config"), e.what());

src/shisen_cpp/config/grpc/call_data_save_capture_setting.cpp

+2-3
Original file line numberDiff line numberDiff line change
@@ -21,9 +21,9 @@
2121
#include <nlohmann/json.hpp>
2222
#include <rclcpp/rclcpp.hpp>
2323
#include <shisen_cpp/config/grpc/call_data_save_capture_setting.hpp>
24-
#include <shisen_cpp/config/utils/config.hpp>
2524
#include <shisen_interfaces/shisen.grpc.pb.h>
2625
#include <shisen_interfaces/shisen.pb.h>
26+
#include <jitsuyo/config.hpp>
2727

2828
namespace shisen_cpp
2929
{
@@ -47,13 +47,12 @@ void CallDataSaveCaptureSetting::WaitForRequest()
4747

4848
void CallDataSaveCaptureSetting::HandleRequest()
4949
{
50-
Config config(path_);
5150
try {
5251
std::string json_string = request_.json_capture();
5352
std::replace(json_string.begin(), json_string.end(), '\\', ' ');
5453
nlohmann::json capture_data = nlohmann::json::parse(json_string);
5554

56-
config.save_capture_setting(capture_data);
55+
jitsuyo::save_config(path_, "capture_settings.json", capture_data);
5756
RCLCPP_INFO(rclcpp::get_logger("Save config"), "config has been saved! ");
5857
} catch (nlohmann::json::exception & e) {
5958
RCLCPP_ERROR(rclcpp::get_logger("Save config"), e.what());

src/shisen_cpp/config/grpc/call_data_set_capture_setting.cpp

+1-2
Original file line numberDiff line numberDiff line change
@@ -20,9 +20,9 @@
2020

2121
#include <rclcpp/rclcpp.hpp>
2222
#include <shisen_cpp/config/grpc/call_data_set_capture_setting.hpp>
23-
#include <shisen_cpp/config/utils/config.hpp>
2423
#include <shisen_interfaces/shisen.grpc.pb.h>
2524
#include <shisen_interfaces/shisen.pb.h>
25+
#include <nlohmann/json.hpp>
2626

2727
namespace shisen_cpp
2828
{
@@ -46,7 +46,6 @@ void CallDataSetCaptureSetting::WaitForRequest()
4646

4747
void CallDataSetCaptureSetting::HandleRequest()
4848
{
49-
Config config(path_);
5049
try {
5150
CaptureSetting capture_setting;
5251

src/shisen_cpp/config/grpc/config.cpp

+7-3
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,7 @@
2525
#include <shisen_cpp/config/grpc/call_data_save_capture_setting.hpp>
2626
#include <shisen_cpp/config/grpc/call_data_set_capture_setting.hpp>
2727
#include <shisen_cpp/config/grpc/config.hpp>
28-
#include <shisen_cpp/config/utils/config.hpp>
28+
#include <jitsuyo/config.hpp>
2929

3030
using grpc::ServerBuilder;
3131
using namespace std::chrono_literals;
@@ -50,9 +50,13 @@ void ConfigGrpc::SignIntHandler(int signum)
5050

5151
void ConfigGrpc::Run(const std::string & path, std::shared_ptr<camera::CameraNode> camera_node)
5252
{
53-
Config config(path);
53+
nlohmann::json grpc_config;
54+
if (!jitsuyo::load_config(path, "grpc.json", grpc_config)) {
55+
RCLCPP_ERROR(rclcpp::get_logger("ConfigGrpc"), "Failed to load grpc config");
56+
return;
57+
}
5458
std::string server_address =
55-
absl::StrFormat("0.0.0.0:%d", config.get_grpc_config()["port"].get<uint16_t>());
59+
absl::StrFormat("0.0.0.0:%d", grpc_config["port"].get<uint16_t>());
5660

5761
ServerBuilder builder;
5862
builder.AddListeningPort(server_address, grpc::InsecureServerCredentials());

src/shisen_cpp/config/utils/config.cpp

-57
This file was deleted.

0 commit comments

Comments
 (0)