|
4 | 4 | #include <string> |
5 | 5 | #include <mutex> |
6 | 6 |
|
7 | | -#include <ICartesianControl.h> |
8 | | - |
9 | 7 | #include <rclcpp/rclcpp.hpp> |
10 | 8 |
|
11 | 9 | #include <geometry_msgs/msg/twist.hpp> |
|
20 | 18 | #include <tf2/LinearMath/Quaternion.h> |
21 | 19 | #include <tf2/LinearMath/Vector3.h> |
22 | 20 |
|
| 21 | +#include <ICartesianControl.h> |
| 22 | + |
23 | 23 | using SetParameters = rcl_interfaces::srv::SetParameters; |
24 | 24 | using Parameter = rcl_interfaces::msg::Parameter; |
25 | 25 | using ParameterValue = rcl_interfaces::msg::ParameterValue; |
26 | 26 | using SetParametersResult = rcl_interfaces::msg::SetParametersResult; |
27 | 27 |
|
| 28 | +/** |
| 29 | + * @ingroup kinematics-dynamics-programs |
| 30 | + * @defgroup SpacenavSubscriber SpacenavSubscriber |
| 31 | + * @brief Creates an instance of SpacenavSubscriber. |
| 32 | + */ |
28 | 33 | class SpacenavSubscriber : public rclcpp::Node |
29 | 34 | { |
30 | 35 | public: |
31 | 36 | SpacenavSubscriber(); |
32 | | - ~SpacenavSubscriber(); |
33 | 37 |
|
34 | 38 | private: |
35 | 39 | void spnav_callback(const sensor_msgs::msg::Joy::SharedPtr msg); |
36 | 40 | void state_callback(const geometry_msgs::msg::PoseStamped::SharedPtr msg); |
37 | | - bool set_preset_streaming_cmd(const std::string &value); |
| 41 | + bool set_preset_streaming_cmd(const std::string &value); |
38 | 42 | SetParametersResult parameter_callback(const std::vector<rclcpp::Parameter> ¶meters); |
39 | 43 | void timer_callback(); |
40 | 44 |
|
41 | 45 | rclcpp::Subscription<sensor_msgs::msg::Joy>::SharedPtr subscription_spnav_{nullptr}; |
42 | 46 | rclcpp::Subscription<geometry_msgs::msg::PoseStamped>::SharedPtr subscription_state_pose_{nullptr}; |
43 | | - |
| 47 | + |
44 | 48 | rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr publisher_spnav_twist_{nullptr}; |
45 | 49 | rclcpp::Publisher<geometry_msgs::msg::Pose>::SharedPtr publisher_spnav_pose_{nullptr}; |
46 | 50 | rclcpp::Publisher<geometry_msgs::msg::Wrench>::SharedPtr publisher_spnav_wrench_{nullptr}; |
@@ -75,6 +79,4 @@ class SpacenavSubscriber : public rclcpp::Node |
75 | 79 | /*Notice that order of gripper_state enum values matches the same order from CartesianControlServerROS2. If modify, please, update*/ |
76 | 80 | enum gripper_state { GRIPPER_NONE, GRIPPER_OPEN, GRIPPER_CLOSE, GRIPPER_STOP }; |
77 | 81 | gripper_state gripper_state_{GRIPPER_NONE}; |
78 | | - |
79 | 82 | }; |
80 | | - |
|
0 commit comments