69 sensor_msgs::msg::JointState m_ros_struct;
73 std::vector<std::string> m_jointNames;
74 std::string m_nodeName;
75 std::string m_jointStateTopicName;
76 std::string m_posTopicName;
77 std::string m_posDirTopicName;
78 std::string m_velTopicName;
79 std::string m_getModesSrvName;
80 std::string m_getPositionSrvName;
81 std::string m_getVelocitySrvName;
82 std::string m_setModesSrvName;
83 std::string m_getJointsNamesSrvName;
84 std::string m_getAvailableModesSrvName;
85 std::map<std::string,size_t> m_quickJointRef;
86 mutable std::mutex m_cmdMutex;
89 std::uint32_t m_counter {0};
94 rclcpp::Publisher<sensor_msgs::msg::JointState>::SharedPtr m_publisher;
95 rclcpp::Node::SharedPtr m_node;
97 static constexpr double m_default_period = 0.02;
101 size_t m_subdevice_joints {0};
115 rclcpp::Subscription<yarp_control_msgs::msg::Position>::SharedPtr m_posSubscription;
116 rclcpp::Subscription<yarp_control_msgs::msg::PositionDirect>::SharedPtr m_posDirectSubscription;
117 rclcpp::Subscription<yarp_control_msgs::msg::Velocity>::SharedPtr m_velSubscription;
118 rclcpp::Service<yarp_control_msgs::srv::GetJointsNames>::SharedPtr m_getJointsNamesSrv;
119 rclcpp::Service<yarp_control_msgs::srv::GetControlModes>::SharedPtr m_getControlModesSrv;
120 rclcpp::Service<yarp_control_msgs::srv::GetPosition>::SharedPtr m_getPositionSrv;
121 rclcpp::Service<yarp_control_msgs::srv::GetVelocity>::SharedPtr m_getVelocitySrv;
122 rclcpp::Service<yarp_control_msgs::srv::SetControlModes>::SharedPtr m_setControlModesSrv;
123 rclcpp::Service<yarp_control_msgs::srv::GetAvailableControlModes>::SharedPtr m_getAvailableModesSrv;
126 bool initRos2Control(
const std::string& name);
130 bool updateAxisName();
133 bool messageVectorsCheck(
const std::string &valueName,
const std::vector<std::string> &names,
const std::vector<double> &ref_values,
const std::vector<double> &derivative);
134 bool messageVectorsCheck(
const std::string &valueName,
const std::vector<std::string> &names,
const std::vector<double> &ref_values);
135 bool messageVectorsCheck(
const std::string &valueName,
const std::vector<std::string> &names,
const std::vector<std::string> &ref_values);
136 bool namesCheck(
const std::vector<std::string> &names);
139 void getControlModesCallback(
const std::shared_ptr<rmw_request_id_t> request_header,
140 const std::shared_ptr<yarp_control_msgs::srv::GetControlModes::Request> request,
141 std::shared_ptr<yarp_control_msgs::srv::GetControlModes::Response> response);
142 void getPositionCallback(
const std::shared_ptr<rmw_request_id_t> request_header,
143 const std::shared_ptr<yarp_control_msgs::srv::GetPosition::Request> request,
144 std::shared_ptr<yarp_control_msgs::srv::GetPosition::Response> response);
145 void getVelocityCallback(
const std::shared_ptr<rmw_request_id_t> request_header,
146 const std::shared_ptr<yarp_control_msgs::srv::GetVelocity::Request> request,
147 std::shared_ptr<yarp_control_msgs::srv::GetVelocity::Response> response);
148 void setControlModesCallback(
const std::shared_ptr<rmw_request_id_t> request_header,
149 const std::shared_ptr<yarp_control_msgs::srv::SetControlModes::Request> request,
150 std::shared_ptr<yarp_control_msgs::srv::SetControlModes::Response> response);
151 void getJointsNamesCallback(
const std::shared_ptr<rmw_request_id_t> request_header,
152 const std::shared_ptr<yarp_control_msgs::srv::GetJointsNames::Request> request,
153 std::shared_ptr<yarp_control_msgs::srv::GetJointsNames::Response> response);
154 void getAvailableModesCallback(
const std::shared_ptr<rmw_request_id_t> request_header,
155 const std::shared_ptr<yarp_control_msgs::srv::GetAvailableControlModes::Request> request,
156 std::shared_ptr<yarp_control_msgs::srv::GetAvailableControlModes::Response> response);
159 void positionTopic_callback(
const yarp_control_msgs::msg::Position::SharedPtr msg);
160 void positionDirectTopic_callback(
const yarp_control_msgs::msg::PositionDirect::SharedPtr msg);
161 void velocityTopic_callback(
const yarp_control_msgs::msg::Velocity::SharedPtr msg);
172 bool close()
override;