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

[Feature] Create Record Image Service #29

Merged
merged 6 commits into from
Jul 2, 2024
Merged
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 CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@ add_library(${PROJECT_NAME} SHARED
"src/${PROJECT_NAME}/config/grpc/call_data_get_image.cpp"
"src/${PROJECT_NAME}/config/grpc/call_data_save_capture_setting.cpp"
"src/${PROJECT_NAME}/config/grpc/call_data_set_capture_setting.cpp"
"src/${PROJECT_NAME}/config/grpc/call_data_record_image.cpp"
"src/${PROJECT_NAME}/utility/capture_setting.cpp"
"src/${PROJECT_NAME}/utility/interface.cpp"
"src/${PROJECT_NAME}/node/shisen_cpp_node.cpp"
Expand Down
1 change: 1 addition & 0 deletions include/shisen_cpp/camera/node/camera_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@ class CameraNode
void update();
void on_mat_captured(cv::Mat mat);
void on_camera_config(int width, int height);
void save_image(cv::Mat mat);
CaptureSetting on_configure_capture_setting(const CaptureSetting & capture_setting);
void configure_capture_setting(const CaptureSetting & capture_setting = CaptureSetting());
void load_configuration(const std::string & path);
Expand Down
45 changes: 45 additions & 0 deletions include/shisen_cpp/config/grpc/call_data_record_image.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,45 @@
// Copyright (c) 2024 ICHIRO ITS
//
// Permission is hereby granted, free of charge, to any person obtaining a copy
// of this software and associated documentation files (the "Software"), to deal
// in the Software without restriction, including without limitation the rights
// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
// copies of the Software, and to permit persons to whom the Software is
// furnished to do so, subject to the following conditions:
//
// The above copyright notice and this permission notice shall be included in
// all copies or substantial portions of the Software.
//
// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL
// THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
// THE SOFTWARE.

#ifndef SHISEN_CPP__CONFIG__GRPC__CALL_DATA_RECORD_IMAGE_HPP__
#define SHISEN_CPP__CONFIG__GRPC__CALL_DATA_RECORD_IMAGE_HPP__

#include <shisen_cpp/camera/node/camera_node.hpp>
#include <shisen_cpp/config/grpc/call_data.hpp>

namespace shisen_cpp
{
class CallDataRecordImage
: CallData<shisen_interfaces::proto::Empty, shisen_interfaces::proto::Empty>
{
public:
CallDataRecordImage(
shisen_interfaces::proto::Config::AsyncService * service, grpc::ServerCompletionQueue * cq,
const std::string & path, const std::shared_ptr<camera::CameraNode>& camera_node);

protected:
void AddNextToCompletionQueue() override;
void WaitForRequest() override;
void HandleRequest() override;
std::shared_ptr<camera::CameraNode> camera_node_;
};
} // namespace shisen_cpp

#endif // SHISEN_CPP__CONFIG__GRPC__CALL_DATA_RECORD_IMAGE_HPP__
34 changes: 30 additions & 4 deletions src/shisen_cpp/camera/node/camera_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,16 +18,16 @@
// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
// THE SOFTWARE.

#include <fstream>
#include <nlohmann/json.hpp>
#include <fstream>
#include <memory>

#include <nlohmann/json.hpp>
#include <opencv2/imgcodecs.hpp>
#include <shisen_cpp/camera/node/camera_node.hpp>
#include <jitsuyo/config.hpp>

#include <chrono>
#include <fstream>
#include <memory>
#include <sstream>
#include <string>

namespace shisen_cpp::camera
Expand Down Expand Up @@ -69,6 +69,32 @@ void CameraNode::on_camera_config(int width, int height)
camera_config_publisher->publish(camera_config_provider->get_camera_config());
}

void CameraNode::save_image(cv::Mat mat)
{
if (!std::filesystem::exists("image")) {
if (!std::filesystem::create_directory("image")) {
RCLCPP_ERROR(node->get_logger(), "Error creating `image` directory!");
return;
}
}

auto now = std::chrono::system_clock::now();
std::time_t now_time_t = std::chrono::system_clock::to_time_t(now);
auto now_ms = std::chrono::duration_cast<std::chrono::milliseconds>(now.time_since_epoch()) % 1000;

std::stringstream ss;
ss << std::put_time(std::localtime(&now_time_t), "%Y-%m-%d_%H-%M-%S");
ss << '-' << std::setfill('0') << std::setw(3) << now_ms.count();
std::string timestamp = ss.str();

std::string filename = "image/" + timestamp + ".jpg";

bool result = cv::imwrite(filename, mat);
if (!result) {
RCLCPP_ERROR(node->get_logger(), "Failed to save image!");
}
}

cv::Mat CameraNode::get_mat()
{
update();
Expand Down
54 changes: 54 additions & 0 deletions src/shisen_cpp/config/grpc/call_data_record_image.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,54 @@
// Copyright (c) 2024 ICHIRO ITS
//
// Permission is hereby granted, free of charge, to any person obtaining a copy
// of this software and associated documentation files (the "Software"), to deal
// in the Software without restriction, including without limitation the rights
// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
// copies of the Software, and to permit persons to whom the Software is
// furnished to do so, subject to the following conditions:
//
// The above copyright notice and this permission notice shall be included in
// all copies or substantial portions of the Software.
//
// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL
// THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
// THE SOFTWARE.

#include <rclcpp/rclcpp.hpp>
#include <shisen_cpp/config/grpc/call_data_record_image.hpp>
#include <shisen_interfaces/shisen.grpc.pb.h>
#include <shisen_interfaces/shisen.pb.h>

namespace shisen_cpp
{
CallDataRecordImage::CallDataRecordImage(
shisen_interfaces::proto::Config::AsyncService * service, grpc::ServerCompletionQueue * cq,
const std::string & path, const std::shared_ptr<camera::CameraNode>& camera_node)
: CallData(service, cq, path), camera_node_(camera_node)
{
Proceed();
}

void CallDataRecordImage::AddNextToCompletionQueue()
{
new CallDataRecordImage(service_, cq_, path_, camera_node_);
}

void CallDataRecordImage::WaitForRequest()
{
service_->RequestRecordImage(&ctx_, &request_, &responder_, cq_, cq_, this);
}

void CallDataRecordImage::HandleRequest()
{
try {
camera_node_->save_image(camera_node_->get_mat());
} catch(const std::exception& e) {
RCLCPP_ERROR(rclcpp::get_logger("Record Image"), e.what());
}
}
} // namespace shisen_cpp
2 changes: 2 additions & 0 deletions src/shisen_cpp/config/grpc/config.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
#include <shisen_cpp/config/grpc/call_data_get_image.hpp>
#include <shisen_cpp/config/grpc/call_data_save_capture_setting.hpp>
#include <shisen_cpp/config/grpc/call_data_set_capture_setting.hpp>
#include <shisen_cpp/config/grpc/call_data_record_image.hpp>
#include <shisen_cpp/config/grpc/config.hpp>
#include <jitsuyo/config.hpp>

Expand Down Expand Up @@ -72,6 +73,7 @@ void ConfigGrpc::Run(const std::string & path, std::shared_ptr<camera::CameraNod
new CallDataSaveCaptureSetting(&service_, cq_.get(), path);
new CallDataSetCaptureSetting(&service_, cq_.get(), path, camera_node);
new CallDataGetImage(&service_, cq_.get(), path, camera_node);
new CallDataRecordImage(&service_, cq_.get(), path, camera_node);
void * tag; // uniquely identifies a request.
bool ok = true;
while (true) {
Expand Down
Loading