1+ #ifndef UR_ROBOT_DRIVER__ROBOT_STATE_HELPER_HPP_
2+ #define UR_ROBOT_DRIVER__ROBOT_STATE_HELPER_HPP_
3+
4+ #include < chrono>
5+
6+ #include " rclcpp/rclcpp.hpp"
7+ #include " rclcpp_action/create_server.hpp"
8+ #include " std_srvs/srv/trigger.hpp"
9+
10+ #include " ur_dashboard_msgs/action/set_mode.hpp"
11+ #include " ur_dashboard_msgs/msg/safety_mode.hpp"
12+ #include " ur_dashboard_msgs/msg/robot_mode.hpp"
13+ #include " ur_client_library/ur/datatypes.h"
14+
15+ namespace ur_robot_driver
16+ {
17+ class RobotStateHelper
18+ {
19+ public:
20+ using SetModeGoalHandle = rclcpp_action::ServerGoalHandle<ur_dashboard_msgs::action::SetMode>;
21+
22+ RobotStateHelper (const rclcpp::Node::SharedPtr& node);
23+ RobotStateHelper () = delete ;
24+ virtual ~RobotStateHelper () = default ;
25+
26+ private:
27+ rclcpp::Node::SharedPtr node_;
28+
29+ void robotModeCallback (ur_dashboard_msgs::msg::RobotMode::SharedPtr msg);
30+ void safetyModeCallback (ur_dashboard_msgs::msg::SafetyMode::SharedPtr msg);
31+
32+ void updateRobotState (bool called_from_thread = false );
33+
34+ void doTransition (bool called_from_thread = false );
35+
36+ bool safeDashboardTrigger (rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr srv, bool called_from_thread = false );
37+
38+ void setModeAcceptCallback (const std::shared_ptr<SetModeGoalHandle> goal_handle);
39+ rclcpp_action::GoalResponse setModeGoalCallback (const rclcpp_action::GoalUUID& uuid,
40+ std::shared_ptr<const ur_dashboard_msgs::action::SetMode::Goal> goal);
41+ rclcpp_action::CancelResponse
42+ setModeCancelCallback (const std::shared_ptr<SetModeGoalHandle> goal_handle);
43+
44+ void setModeExecute (const std::shared_ptr<SetModeGoalHandle> goal_handle);
45+
46+ void startActionServer ();
47+ bool is_started_;
48+
49+ std::shared_ptr<ur_dashboard_msgs::action::SetMode::Result> result_;
50+ std::shared_ptr<ur_dashboard_msgs::action::SetMode::Feedback> feedback_;
51+ std::shared_ptr<const ur_dashboard_msgs::action::SetMode::Goal> goal_;
52+ std::shared_ptr<SetModeGoalHandle> current_goal_handle_;
53+
54+ urcl::RobotMode robot_mode_;
55+ urcl::SafetyMode safety_mode_;
56+
57+ rclcpp_action::Server<ur_dashboard_msgs::action::SetMode>::SharedPtr set_mode_as_;
58+
59+ rclcpp::Subscription<ur_dashboard_msgs::msg::RobotMode>::SharedPtr robot_mode_sub_;
60+ rclcpp::Subscription<ur_dashboard_msgs::msg::SafetyMode>::SharedPtr safety_mode_sub_;
61+
62+ rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr unlock_protective_stop_srv_;
63+ rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr restart_safety_srv_;
64+ rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr power_on_srv_;
65+ rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr power_off_srv_;
66+ rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr brake_release_srv_;
67+ rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr stop_program_srv_;
68+ rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr play_program_srv_;
69+ };
70+ } // namespace ur_robot_driver
71+
72+ #endif // UR_ROBOT_DRIVER__ROBOT_STATE_HELPER_HPP_
0 commit comments