@@ -36,6 +36,8 @@ RobotControlServiceImpl::RobotControlServiceImpl(
3636 RCLCPP_INFO (get_logger (), " > Frequency ratio for servo re-publishig is %i" , servo_frequency_ratio_);
3737
3838 switch_controller_client_ = node_->create_client <controller_manager_msgs::srv::SwitchController>(" /controller_manager/switch_controller" );
39+ start_servo_client_ = node_->create_client <std_srvs::srv::Trigger>(" /servo_node/start_servo" );
40+ stop_servo_client_ = node_->create_client <std_srvs::srv::Trigger>(" /servo_node/stop_servo" );
3941 servo_joint_pub_ = node_->create_publisher <control_msgs::msg::JointJog>(
4042 node_->get_parameter (" topic_servo_joint" ).as_string (), 10 );
4143 servo_tcp_pub_ = node_->create_publisher <geometry_msgs::msg::TwistStamped>(
@@ -101,6 +103,40 @@ bool RobotControlServiceImpl::SwitchControllers(
101103 return future.get ()->ok ;
102104}
103105
106+ bool RobotControlServiceImpl::CallServoStartService () {
107+ if (!start_servo_client_->wait_for_service (action_timeout_)) {
108+ RCLCPP_WARN (get_logger (), " Service `/servo_node/start_servo` not available." );
109+ return false ;
110+ }
111+
112+ auto request = std::make_shared<std_srvs::srv::Trigger::Request>();
113+ auto result_future = start_servo_client_->async_send_request (request);
114+
115+ if (result_future.wait_for (action_timeout_) != std::future_status::ready) {
116+ RCLCPP_WARN (get_logger (), " Service `/servo_node/start_servo` call timed out." );
117+ return false ;
118+ }
119+ auto result = result_future.get ();
120+ return result->success ;
121+ }
122+
123+ bool RobotControlServiceImpl::CallServoStopService () {
124+ if (!stop_servo_client_->wait_for_service (action_timeout_)) {
125+ RCLCPP_WARN (get_logger (), " Service `/servo_node/stop_servo` not available." );
126+ return false ;
127+ }
128+
129+ auto request = std::make_shared<std_srvs::srv::Trigger::Request>();
130+ auto result_future = stop_servo_client_->async_send_request (request);
131+
132+ if (result_future.wait_for (action_timeout_) != std::future_status::ready) {
133+ RCLCPP_WARN (get_logger (), " Service `/servo_node/stop_servo` call timed out." );
134+ return false ;
135+ }
136+ auto result = result_future.get ();
137+ return result->success ;
138+ }
139+
104140grpc::Status RobotControlServiceImpl::ServoEnable (
105141 grpc::ServerContext*,
106142 const google::protobuf::Empty*,
@@ -117,13 +153,21 @@ grpc::Status RobotControlServiceImpl::ServoEnable(
117153 return grpc::Status (grpc::StatusCode::INTERNAL, err);
118154 }
119155
156+ if (!CallServoStartService ()) {
157+ std::string err = " Failed to start servo service." ;
158+ RCLCPP_WARN (get_logger (), " [RobotControlService][ServoEnable] %s" , err.c_str ());
159+ response->set_msg (err);
160+ return grpc::Status (grpc::StatusCode::INTERNAL, err);
161+ }
162+
120163 {
121164 std::lock_guard<std::mutex> lock (servo_mutex_);
122165 servo_mode_ = ServoMode::JointJog;
123166 }
124167
125168 response->set_success (true );
126169 response->set_msg (" " );
170+ RCLCPP_INFO (get_logger (), " [RobotControlService][ServoDisable] Servo enabled" );
127171 return grpc::Status::OK;
128172}
129173
@@ -134,6 +178,13 @@ grpc::Status RobotControlServiceImpl::ServoDisable(
134178{
135179 response->set_success (false );
136180
181+ if (!CallServoStopService ()) {
182+ std::string err = " Failed to stop servo service." ;
183+ RCLCPP_WARN (get_logger (), " [RobotControlService][ServoDisable] %s" , err.c_str ());
184+ response->set_msg (err);
185+ return grpc::Status (grpc::StatusCode::INTERNAL, err);
186+ }
187+
137188 if (!SwitchControllers (
138189 {" scaled_joint_trajectory_controller" },
139190 {" forward_position_controller" })) {
@@ -152,6 +203,7 @@ grpc::Status RobotControlServiceImpl::ServoDisable(
152203
153204 response->set_success (true );
154205 response->set_msg (" " );
206+ RCLCPP_INFO (get_logger (), " [RobotControlService][ServoDisable] Servo disabled" );
155207 return grpc::Status::OK;
156208}
157209
0 commit comments