Skip to content

Commit

Permalink
Create more specific aliases (review #38)
Browse files Browse the repository at this point in the history
  • Loading branch information
nikhil-sethi committed Oct 16, 2024
1 parent e01f161 commit d1e8e95
Show file tree
Hide file tree
Showing 2 changed files with 30 additions and 23 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down Expand Up @@ -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
Expand Down Expand Up @@ -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;

Expand Down
16 changes: 8 additions & 8 deletions micro_epsilon_scancontrol_driver/src/driver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand All @@ -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);
Expand All @@ -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);
}
Expand Down

0 comments on commit d1e8e95

Please sign in to comment.