From d1e8e9559594703e9097ee67cfb3a0ec3468cb42 Mon Sep 17 00:00:00 2001 From: Nikhil Sethi <sethi.nirvil@gmail.com> Date: Wed, 16 Oct 2024 15:59:45 +0200 Subject: [PATCH] Create more specific aliases (review #38) --- .../micro_epsilon_scancontrol_driver/driver.h | 37 +++++++++++-------- .../src/driver.cpp | 16 ++++---- 2 files changed, 30 insertions(+), 23 deletions(-) diff --git a/micro_epsilon_scancontrol_driver/include/micro_epsilon_scancontrol_driver/driver.h b/micro_epsilon_scancontrol_driver/include/micro_epsilon_scancontrol_driver/driver.h index 3666323..e7b16db 100644 --- a/micro_epsilon_scancontrol_driver/include/micro_epsilon_scancontrol_driver/driver.h +++ b/micro_epsilon_scancontrol_driver/include/micro_epsilon_scancontrol_driver/driver.h @@ -34,12 +34,19 @@ typedef pcl::PointCloud<pcl::PointXYZI> point_cloud_t; namespace scancontrol_driver { - // aliases - using set_duration_srv = micro_epsilon_scancontrol_msgs::srv::SetDuration; - using get_duration_srv = micro_epsilon_scancontrol_msgs::srv::GetDuration; class ScanControlDriver: public rclcpp::Node { + // aliases + using SetDurationSrv = micro_epsilon_scancontrol_msgs::srv::SetDuration; + using SetDurationRequest = SetDurationSrv::Request; + using SetDurationResponse = SetDurationSrv::Response; + + using GetDurationSrv = micro_epsilon_scancontrol_msgs::srv::GetDuration; + using GetDurationRequest = GetDurationSrv::Request; + using GetDurationResponse = GetDurationSrv::Response; + + public: // Constructor and destructor explicit ScanControlDriver(const std::string& name); @@ -85,17 +92,17 @@ namespace scancontrol_driver const std::shared_ptr<std_srvs::srv::SetBool::Request> request, std::shared_ptr<std_srvs::srv::SetBool::Response> response); void ServiceSetExposureDuration( - const std::shared_ptr<set_duration_srv::Request> request, - std::shared_ptr<set_duration_srv::Response> response); + const std::shared_ptr<SetDurationRequest> request, + std::shared_ptr<SetDurationResponse> response); void ServiceGetExposureDuration( - const std::shared_ptr<get_duration_srv::Request> request, - std::shared_ptr<get_duration_srv::Response> response); + const std::shared_ptr<GetDurationRequest> request, + std::shared_ptr<GetDurationResponse> response); void ServiceSetIdleDuration( - const std::shared_ptr<set_duration_srv::Request> request, - std::shared_ptr<set_duration_srv::Response> response); + const std::shared_ptr<SetDurationRequest> request, + std::shared_ptr<SetDurationResponse> response); void ServiceGetIdleDuration( - const std::shared_ptr<get_duration_srv::Request> request, - std::shared_ptr<get_duration_srv::Response> response); + const std::shared_ptr<GetDurationRequest> request, + std::shared_ptr<GetDurationResponse> response); private: // Profile functions @@ -125,10 +132,10 @@ namespace scancontrol_driver rclcpp::Service<micro_epsilon_scancontrol_msgs::srv::GetResolution>::SharedPtr get_resolution_srv; rclcpp::Service<micro_epsilon_scancontrol_msgs::srv::SetResolution>::SharedPtr set_resolution_srv; rclcpp::Service<micro_epsilon_scancontrol_msgs::srv::GetAvailableResolutions>::SharedPtr get_available_resolutions_srv; - rclcpp::Service<set_duration_srv>::SharedPtr set_exposure_duration_srv; - rclcpp::Service<get_duration_srv>::SharedPtr get_exposure_duration_srv; - rclcpp::Service<set_duration_srv>::SharedPtr set_idle_duration_srv; - rclcpp::Service<get_duration_srv>::SharedPtr get_idle_duration_srv; + rclcpp::Service<SetDurationSrv>::SharedPtr set_exposure_duration_srv; + rclcpp::Service<GetDurationSrv>::SharedPtr get_exposure_duration_srv; + rclcpp::Service<SetDurationSrv>::SharedPtr set_idle_duration_srv; + rclcpp::Service<GetDurationSrv>::SharedPtr get_idle_duration_srv; rclcpp::Service<std_srvs::srv::SetBool>::SharedPtr invert_z_srv; rclcpp::Service<std_srvs::srv::SetBool>::SharedPtr invert_x_srv; diff --git a/micro_epsilon_scancontrol_driver/src/driver.cpp b/micro_epsilon_scancontrol_driver/src/driver.cpp index b9f0fe7..dc0697d 100644 --- a/micro_epsilon_scancontrol_driver/src/driver.cpp +++ b/micro_epsilon_scancontrol_driver/src/driver.cpp @@ -618,8 +618,8 @@ namespace scancontrol_driver // a wrapper on setfeature to use proper encoding void ScanControlDriver::ServiceSetExposureDuration( - const std::shared_ptr<set_duration_srv::Request> request, - std::shared_ptr<set_duration_srv::Response> response){ + const std::shared_ptr<SetDurationRequest> request, + std::shared_ptr<SetDurationResponse> response){ int ret_code = SetDuration(FEATURE_FUNCTION_EXPOSURE_TIME, request->duration); response->success = !(ret_code < GENERAL_FUNCTION_OK); @@ -628,16 +628,16 @@ namespace scancontrol_driver // a wrapper on getfeature to use proper decoding void ScanControlDriver::ServiceGetExposureDuration( - const std::shared_ptr<get_duration_srv::Request> request, - std::shared_ptr<get_duration_srv::Response> response){ + const std::shared_ptr<GetDurationRequest> request, + std::shared_ptr<GetDurationResponse> response){ response->return_code = GetDuration(FEATURE_FUNCTION_EXPOSURE_TIME, &(response->duration)); response->success = !(response->return_code < GENERAL_FUNCTION_OK); } // a wrapper on setfeature to use proper encoding void ScanControlDriver::ServiceSetIdleDuration( - const std::shared_ptr<set_duration_srv::Request> request, - std::shared_ptr<set_duration_srv::Response> response){ + const std::shared_ptr<SetDurationRequest> request, + std::shared_ptr<SetDurationResponse> response){ int ret_code = SetDuration(FEATURE_FUNCTION_IDLE_TIME, request->duration); response->success = !(ret_code < GENERAL_FUNCTION_OK); @@ -646,8 +646,8 @@ namespace scancontrol_driver // a wrapper on getfeature to use proper decoding void ScanControlDriver::ServiceGetIdleDuration( - const std::shared_ptr<get_duration_srv::Request> request, - std::shared_ptr<get_duration_srv::Response> response){ + const std::shared_ptr<GetDurationRequest> request, + std::shared_ptr<GetDurationResponse> response){ response->return_code = GetDuration(FEATURE_FUNCTION_IDLE_TIME, &(response->duration)); response->success = !(response->return_code < GENERAL_FUNCTION_OK); }