|
18 | 18 | #include <moveit/move_group_interface/move_group_interface.h> |
19 | 19 | #include <std_srvs/srv/trigger.hpp> |
20 | 20 |
|
21 | | - |
22 | 21 | namespace aegis_grpc { |
23 | 22 |
|
24 | | -class RobotControlServiceImpl final |
25 | | - : public proto_aegis_grpc::v1::RobotControlService::Service { |
26 | | - public: |
27 | | - using GripperCommand = control_msgs::action::GripperCommand; |
28 | | - using GoalHandleGripper = rclcpp_action::ClientGoalHandle<GripperCommand>; |
29 | | - |
30 | | - enum class ServoMode { |
31 | | - None, |
32 | | - JointJog, |
33 | | - TCPTwist |
34 | | - }; |
35 | | - |
36 | | - explicit RobotControlServiceImpl(std::shared_ptr<rclcpp::Node> node); |
37 | | - |
38 | | - // TODO(issue#87) Create additional methods to enable and disable servo control. |
39 | | - grpc::Status ServoEnable( |
40 | | - grpc::ServerContext* context, |
41 | | - const google::protobuf::Empty* request, |
42 | | - proto_aegis_grpc::v1::TriggerResponse* response) override; |
43 | | - |
44 | | - grpc::Status ServoDisable( |
45 | | - grpc::ServerContext* context, |
46 | | - const google::protobuf::Empty* request, |
47 | | - proto_aegis_grpc::v1::TriggerResponse* response) override; |
48 | | - |
49 | | - grpc::Status ServoJoint( |
50 | | - grpc::ServerContext* context, |
51 | | - const proto_aegis_grpc::v1::JointJog* request, |
52 | | - google::protobuf::Empty* response) override; |
53 | | - |
54 | | - grpc::Status ServoTCP( |
55 | | - grpc::ServerContext* context, |
56 | | - const proto_aegis_grpc::v1::Twist* request, |
57 | | - google::protobuf::Empty* response) override; |
58 | | - |
59 | | - grpc::Status GotoPose( |
60 | | - grpc::ServerContext* context, |
61 | | - const proto_aegis_grpc::v1::Pose* request, |
62 | | - proto_aegis_grpc::v1::TriggerResponse* response) override; |
63 | | - |
64 | | - grpc::Status GotoJoints( |
65 | | - grpc::ServerContext* context, |
66 | | - const proto_aegis_grpc::v1::JointState* request, |
67 | | - proto_aegis_grpc::v1::TriggerResponse* response) override; |
68 | | - |
69 | | - grpc::Status GripperSetPosition( |
70 | | - grpc::ServerContext* context, |
71 | | - const proto_aegis_grpc::v1::GripperSetPositionRequest* request, |
72 | | - proto_aegis_grpc::v1::TriggerResponse* response) override; |
73 | | - |
74 | | - grpc::Status GripperClose( |
75 | | - grpc::ServerContext* context, |
76 | | - const google::protobuf::Empty* request, |
77 | | - proto_aegis_grpc::v1::TriggerResponse* response) override; |
78 | | - |
79 | | - grpc::Status GripperOpen( |
80 | | - grpc::ServerContext* context, |
81 | | - const google::protobuf::Empty* request, |
82 | | - proto_aegis_grpc::v1::TriggerResponse* response) override; |
83 | | - |
84 | | - private: |
85 | | - bool SwitchControllers( |
86 | | - const std::vector<std::string>& activate, |
87 | | - const std::vector<std::string>& deactivate); |
88 | | - bool CallServoStartService(); |
89 | | - bool CallServoStopService(); |
90 | | - |
91 | | - void ServoPublishLoop(); |
92 | | - void GripperSendGoal(double position, double max_effort); |
93 | | - |
94 | | - rclcpp::Logger get_logger() const; |
95 | | - |
96 | | - template <class T> |
97 | | - void DeclareROSParameter(const std::string& name, const T& default_val, const std::string& description); |
98 | | - |
99 | | - std::shared_ptr<rclcpp::Node> node_; |
100 | | - std::unique_ptr<moveit::planning_interface::MoveGroupInterface> move_group_; |
101 | | - |
102 | | - rclcpp::Client<controller_manager_msgs::srv::SwitchController>::SharedPtr switch_controller_client_; |
103 | | - rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr start_servo_client_; |
104 | | - rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr stop_servo_client_; |
105 | | - rclcpp::Publisher<control_msgs::msg::JointJog>::SharedPtr servo_joint_pub_; |
106 | | - rclcpp::Publisher<geometry_msgs::msg::TwistStamped>::SharedPtr servo_tcp_pub_; |
107 | | - rclcpp_action::Client<GripperCommand>::SharedPtr gripper_client_; |
108 | | - rclcpp::TimerBase::SharedPtr servo_pub_timer_; |
109 | | - |
110 | | - std::mutex servo_mutex_; |
111 | | - ServoMode servo_mode_; |
112 | | - std::string servo_tcp_link_; |
113 | | - control_msgs::msg::JointJog servo_joint_msg_; |
114 | | - geometry_msgs::msg::Twist servo_tcp_msg_; |
115 | | - int servo_frequency_ratio_; |
116 | | - int servo_msgs_left_; |
117 | | - |
118 | | - std::mutex gripper_mutex_; |
119 | | - std::atomic<bool> gripper_in_use_; |
120 | | - std::chrono::duration<double> action_timeout_; |
121 | | - std::string gripper_cmd_msg_; |
122 | | - bool gripper_cmd_success_; |
123 | | - std::atomic<bool> gripper_cmd_done_; |
| 23 | +class RobotControlServiceImpl final : public proto_aegis_grpc::v1::RobotControlService::Service { |
| 24 | + public: |
| 25 | + using GripperCommand = control_msgs::action::GripperCommand; |
| 26 | + using GoalHandleGripper = rclcpp_action::ClientGoalHandle<GripperCommand>; |
| 27 | + |
| 28 | + enum class ServoMode { None, JointJog, TCPTwist }; |
| 29 | + |
| 30 | + explicit RobotControlServiceImpl(std::shared_ptr<rclcpp::Node> node); |
| 31 | + |
| 32 | + // TODO(issue#87) Create additional methods to enable and disable servo control. |
| 33 | + grpc::Status ServoEnable(grpc::ServerContext* context, |
| 34 | + const google::protobuf::Empty* request, |
| 35 | + proto_aegis_grpc::v1::TriggerResponse* response) override; |
| 36 | + |
| 37 | + grpc::Status ServoDisable(grpc::ServerContext* context, |
| 38 | + const google::protobuf::Empty* request, |
| 39 | + proto_aegis_grpc::v1::TriggerResponse* response) override; |
| 40 | + |
| 41 | + grpc::Status ServoJoint(grpc::ServerContext* context, |
| 42 | + const proto_aegis_grpc::v1::JointJog* request, |
| 43 | + google::protobuf::Empty* response) override; |
| 44 | + |
| 45 | + grpc::Status ServoTCP(grpc::ServerContext* context, |
| 46 | + const proto_aegis_grpc::v1::Twist* request, |
| 47 | + google::protobuf::Empty* response) override; |
| 48 | + |
| 49 | + grpc::Status GotoPose(grpc::ServerContext* context, |
| 50 | + const proto_aegis_grpc::v1::Pose* request, |
| 51 | + proto_aegis_grpc::v1::TriggerResponse* response) override; |
| 52 | + |
| 53 | + grpc::Status GotoJoints(grpc::ServerContext* context, |
| 54 | + const proto_aegis_grpc::v1::JointState* request, |
| 55 | + proto_aegis_grpc::v1::TriggerResponse* response) override; |
| 56 | + |
| 57 | + grpc::Status GripperSetPosition(grpc::ServerContext* context, |
| 58 | + const proto_aegis_grpc::v1::GripperSetPositionRequest* request, |
| 59 | + proto_aegis_grpc::v1::TriggerResponse* response) override; |
| 60 | + |
| 61 | + grpc::Status GripperClose(grpc::ServerContext* context, |
| 62 | + const google::protobuf::Empty* request, |
| 63 | + proto_aegis_grpc::v1::TriggerResponse* response) override; |
| 64 | + |
| 65 | + grpc::Status GripperOpen(grpc::ServerContext* context, |
| 66 | + const google::protobuf::Empty* request, |
| 67 | + proto_aegis_grpc::v1::TriggerResponse* response) override; |
| 68 | + |
| 69 | + private: |
| 70 | + bool SwitchControllers(const std::vector<std::string>& activate, const std::vector<std::string>& deactivate); |
| 71 | + bool CallServoStartService(); |
| 72 | + bool CallServoStopService(); |
| 73 | + |
| 74 | + void ServoPublishLoop(); |
| 75 | + void GripperSendGoal(double position, double max_effort); |
| 76 | + |
| 77 | + rclcpp::Logger get_logger() const; |
| 78 | + |
| 79 | + template <class T> |
| 80 | + void DeclareROSParameter(const std::string& name, const T& default_val, const std::string& description); |
| 81 | + |
| 82 | + std::shared_ptr<rclcpp::Node> node_; |
| 83 | + std::unique_ptr<moveit::planning_interface::MoveGroupInterface> move_group_; |
| 84 | + |
| 85 | + rclcpp::Client<controller_manager_msgs::srv::SwitchController>::SharedPtr switch_controller_client_; |
| 86 | + rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr start_servo_client_; |
| 87 | + rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr stop_servo_client_; |
| 88 | + rclcpp::Publisher<control_msgs::msg::JointJog>::SharedPtr servo_joint_pub_; |
| 89 | + rclcpp::Publisher<geometry_msgs::msg::TwistStamped>::SharedPtr servo_tcp_pub_; |
| 90 | + rclcpp_action::Client<GripperCommand>::SharedPtr gripper_client_; |
| 91 | + rclcpp::TimerBase::SharedPtr servo_pub_timer_; |
| 92 | + |
| 93 | + std::mutex servo_mutex_; |
| 94 | + ServoMode servo_mode_; |
| 95 | + std::string servo_tcp_link_; |
| 96 | + control_msgs::msg::JointJog servo_joint_msg_; |
| 97 | + geometry_msgs::msg::Twist servo_tcp_msg_; |
| 98 | + int servo_frequency_ratio_; |
| 99 | + int servo_msgs_left_; |
| 100 | + |
| 101 | + std::mutex gripper_mutex_; |
| 102 | + std::atomic<bool> gripper_in_use_; |
| 103 | + std::chrono::duration<double> action_timeout_; |
| 104 | + std::string gripper_cmd_msg_; |
| 105 | + bool gripper_cmd_success_; |
| 106 | + std::atomic<bool> gripper_cmd_done_; |
124 | 107 | }; |
125 | 108 |
|
126 | | -} // namespace aegis_grpc |
| 109 | +} // namespace aegis_grpc |
127 | 110 | #endif // AEGIS_GRPC__ROBOT_CONTROL_SERVICE_HPP_ |
0 commit comments