diff --git a/aegis_grpc/CHANGELOG.md b/aegis_grpc/CHANGELOG.md index 9a27983..4ef257f 100644 --- a/aegis_grpc/CHANGELOG.md +++ b/aegis_grpc/CHANGELOG.md @@ -9,6 +9,7 @@ and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0 ### Added +* [PR-96](https://github.com/AGH-CEAI/aegis_ros/pull/96) - Added gRPC servo controller switching. * [PR-92](https://github.com/AGH-CEAI/aegis_ros/pull/92) - Added Python client installation script. * [PR-88](https://github.com/AGH-CEAI/aegis_ros/pull/88) - Added gRPC robot motion commands with MoveIt. * [PR-88](https://github.com/AGH-CEAI/aegis_ros/pull/88) - MVP of the gRPC Python client. diff --git a/aegis_grpc/CMakeLists.txt b/aegis_grpc/CMakeLists.txt index 8017620..d96184a 100644 --- a/aegis_grpc/CMakeLists.txt +++ b/aegis_grpc/CMakeLists.txt @@ -18,6 +18,7 @@ find_package(ament_cmake REQUIRED) set(ROS_DEPENDS rclcpp rclcpp_action + controller_manager_msgs control_msgs geometry_msgs sensor_msgs diff --git a/aegis_grpc/include/aegis_grpc/robot_control_service.hpp b/aegis_grpc/include/aegis_grpc/robot_control_service.hpp index c9f1e6f..e02311a 100644 --- a/aegis_grpc/include/aegis_grpc/robot_control_service.hpp +++ b/aegis_grpc/include/aegis_grpc/robot_control_service.hpp @@ -9,6 +9,7 @@ #include #include +#include #include #include #include @@ -34,6 +35,16 @@ class RobotControlServiceImpl final explicit RobotControlServiceImpl(std::shared_ptr node); // TODO(issue#87) Create additional methods to enable and disable servo control. + grpc::Status ServoEnable( + grpc::ServerContext* context, + const google::protobuf::Empty* request, + proto_aegis_grpc::v1::TriggerResponse* response) override; + + grpc::Status ServoDisable( + grpc::ServerContext* context, + const google::protobuf::Empty* request, + proto_aegis_grpc::v1::TriggerResponse* response) override; + grpc::Status ServoJoint( grpc::ServerContext* context, const proto_aegis_grpc::v1::JointJog* request, @@ -70,17 +81,22 @@ class RobotControlServiceImpl final proto_aegis_grpc::v1::TriggerResponse* response) override; private: + bool SwitchControllers( + const std::vector& activate, + const std::vector& deactivate); + + void ServoPublishLoop(); + void GripperSendGoal(double position, double max_effort); + rclcpp::Logger get_logger() const; template void DeclareROSParameter(const std::string& name, const T& default_val, const std::string& description); - void ServoPublishLoop(); - void GripperSendGoal(double position, double max_effort); - std::shared_ptr node_; std::unique_ptr move_group_; + rclcpp::Client::SharedPtr switch_controller_client_; rclcpp::Publisher::SharedPtr servo_joint_pub_; rclcpp::Publisher::SharedPtr servo_tcp_pub_; rclcpp_action::Client::SharedPtr gripper_client_; diff --git a/aegis_grpc/package.xml b/aegis_grpc/package.xml index 0bc5628..8e793ea 100644 --- a/aegis_grpc/package.xml +++ b/aegis_grpc/package.xml @@ -12,11 +12,13 @@ https://github.com/AGH-CEAI/aegis_ros/issues Maciej Aleksandrowicz + Jakub Plachno ament_cmake ament_cmake_python control_msgs + controller_manager_msgs geometry_msgs libgrpc moveit_msgs diff --git a/aegis_grpc/proto_aegis_grpc/v1/robot_srvs.proto b/aegis_grpc/proto_aegis_grpc/v1/robot_srvs.proto index de6c3fc..35496f8 100644 --- a/aegis_grpc/proto_aegis_grpc/v1/robot_srvs.proto +++ b/aegis_grpc/proto_aegis_grpc/v1/robot_srvs.proto @@ -21,6 +21,8 @@ message RobotState { } service RobotControlService { + rpc ServoEnable(google.protobuf.Empty) returns (TriggerResponse); + rpc ServoDisable(google.protobuf.Empty) returns (TriggerResponse); rpc ServoJoint(JointJog) returns (google.protobuf.Empty); rpc ServoTCP(Twist) returns (google.protobuf.Empty); rpc GotoPose(Pose) returns (TriggerResponse); diff --git a/aegis_grpc/python_client/aegis_grpc_client/grpc_client.py b/aegis_grpc/python_client/aegis_grpc_client/grpc_client.py index 80cc3e2..6c83b5c 100644 --- a/aegis_grpc/python_client/aegis_grpc_client/grpc_client.py +++ b/aegis_grpc/python_client/aegis_grpc_client/grpc_client.py @@ -396,3 +396,19 @@ async def gripper_open(self) -> tuple[bool, str]: except grpc.RpcError as e: self.logger.error(f"GripperOpen failed: {e}") raise + + async def servo_enable(self) -> tuple[bool, str]: + self._check_connected() + try: + resp = await self.control_stub.ServoEnable(Empty()) + return resp.success, resp.msg + except grpc.RpcError as e: + raise RuntimeError("Failed to enable servo") from e + + async def servo_disable(self) -> tuple[bool, str]: + self._check_connected() + try: + resp = await self.control_stub.ServoDisable(Empty()) + return resp.success, resp.msg + except grpc.RpcError as e: + raise RuntimeError("Failed to disable servo") from e diff --git a/aegis_grpc/src/robot_control_service.cpp b/aegis_grpc/src/robot_control_service.cpp index 7fc84f4..9800667 100644 --- a/aegis_grpc/src/robot_control_service.cpp +++ b/aegis_grpc/src/robot_control_service.cpp @@ -35,6 +35,7 @@ RobotControlServiceImpl::RobotControlServiceImpl( servo_frequency_ratio_ = std::round(servo_out_hz / servo_in_hz); RCLCPP_INFO(get_logger(), "> Frequency ratio for servo re-publishig is %i", servo_frequency_ratio_); + switch_controller_client_ = node_->create_client("/controller_manager/switch_controller"); servo_joint_pub_ = node_->create_publisher( node_->get_parameter("topic_servo_joint").as_string(), 10); servo_tcp_pub_ = node_->create_publisher( @@ -75,6 +76,85 @@ void RobotControlServiceImpl::DeclareROSParameter( p.value_to_string().c_str()); } +bool RobotControlServiceImpl::SwitchControllers( + const std::vector& activate, + const std::vector& deactivate) { + auto req = std::make_shared(); + + req->activate_controllers = activate; + req->deactivate_controllers = deactivate; + req->strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT; + + if (!switch_controller_client_->wait_for_service(action_timeout_)) { + RCLCPP_WARN(get_logger(), "Switch controller service not available"); + return false; + } + + auto future = switch_controller_client_->async_send_request(req); + auto status = future.wait_for(action_timeout_); + + if (status != std::future_status::ready || !future.valid()) { + RCLCPP_WARN(get_logger(), "Switch controller call failed or timed out."); + return false; + } + + return future.get()->ok; +} + +grpc::Status RobotControlServiceImpl::ServoEnable( + grpc::ServerContext*, + const google::protobuf::Empty*, + proto_aegis_grpc::v1::TriggerResponse* response) +{ + response->set_success(false); + + if (!SwitchControllers( + {"forward_position_controller"}, + {"scaled_joint_trajectory_controller"})) { + std::string err = "Controller switch failed."; + RCLCPP_WARN(get_logger(), "[RobotControlService][ServoEnable] %s", err.c_str()); + response->set_msg(err); + return grpc::Status(grpc::StatusCode::INTERNAL, err); + } + + { + std::lock_guard lock(servo_mutex_); + servo_mode_ = ServoMode::JointJog; + } + + response->set_success(true); + response->set_msg(""); + return grpc::Status::OK; +} + +grpc::Status RobotControlServiceImpl::ServoDisable( + grpc::ServerContext*, + const google::protobuf::Empty*, + proto_aegis_grpc::v1::TriggerResponse* response) +{ + response->set_success(false); + + if (!SwitchControllers( + {"scaled_joint_trajectory_controller"}, + {"forward_position_controller"})) { + + std::string err = "Controller switch failed."; + RCLCPP_WARN(get_logger(), "[RobotControlService][ServoDisable] %s", err.c_str()); + response->set_msg(err); + return grpc::Status(grpc::StatusCode::INTERNAL, err); + } + + { + std::lock_guard lock(servo_mutex_); + servo_mode_ = ServoMode::None; + servo_msgs_left_ = 0; + } + + response->set_success(true); + response->set_msg(""); + return grpc::Status::OK; +} + void RobotControlServiceImpl::ServoPublishLoop() { static ServoMode mode; static control_msgs::msg::JointJog jog_msg;