6#ifndef _USE_MATH_DEFINES
7#define _USE_MATH_DEFINES
21#include <rcutils/logging_macros.h>
23using namespace std::chrono_literals;
46void ControlBoard_nws_ros2::closePorts()
76 m_publisher = m_node->create_publisher<sensor_msgs::msg::JointState>(
m_topic_name, 10);
82bool ControlBoard_nws_ros2::initRos2Control(
const std::string& name){
84 m_posTopicName = name+
"/position";
85 m_posDirTopicName = name+
"/position_direct";
86 m_velTopicName = name+
"/velocity";
87 m_getModesSrvName = name+
"/get_modes";
88 m_setModesSrvName = name+
"/set_modes";
89 m_getVelocitySrvName = name+
"/get_velocity";
90 m_getPositionSrvName = name+
"/get_position";
91 m_getAvailableModesSrvName = name+
"/get_available_modes";
92 m_getJointsNamesSrvName = name+
"/get_joints_names";
96 if(m_iPositionControl){
97 m_posSubscription = m_node->create_subscription<yarp_control_msgs::msg::Position>(m_posTopicName, 10,
98 std::bind(&ControlBoard_nws_ros2::positionTopic_callback,
99 this, std::placeholders::_1));
100 if(!m_posSubscription){
102 RCLCPP_ERROR(m_node->get_logger(),
"Could not initialize the Position msg subscription");
107 if(m_iPositionDirect){
108 m_posDirectSubscription = m_node->create_subscription<yarp_control_msgs::msg::PositionDirect>(m_posDirTopicName, 10,
109 std::bind(&ControlBoard_nws_ros2::positionDirectTopic_callback,
110 this, std::placeholders::_1));
111 if(!m_posDirectSubscription){
113 RCLCPP_ERROR(m_node->get_logger(),
"Could not initialize the Position direct msg subscription");
118 if(m_iVelocityControl){
119 m_velSubscription = m_node->create_subscription<yarp_control_msgs::msg::Velocity>(m_velTopicName, 10,
120 std::bind(&ControlBoard_nws_ros2::velocityTopic_callback,
121 this, std::placeholders::_1));
122 if(!m_velSubscription){
124 RCLCPP_ERROR(m_node->get_logger(),
"Could not initialize the Velocity msg subscription");
144 qos.liveliness_lease_duration=time;
148 qos.avoid_ros_namespace_conventions =
true;
149 m_getControlModesSrv = m_node->create_service<yarp_control_msgs::srv::GetControlModes>(m_getModesSrvName,
150 std::bind(&ControlBoard_nws_ros2::getControlModesCallback,
151 this,std::placeholders::_1,std::placeholders::_2,
152 std::placeholders::_3));
153 if(!m_getControlModesSrv){
155 RCLCPP_ERROR(m_node->get_logger(),
"Could not initialize the GetControlModes service");
159 m_getPositionSrv = m_node->create_service<yarp_control_msgs::srv::GetPosition>(m_getPositionSrvName,
160 std::bind(&ControlBoard_nws_ros2::getPositionCallback,
161 this,std::placeholders::_1,std::placeholders::_2,
162 std::placeholders::_3));
163 if(!m_getPositionSrv){
165 RCLCPP_ERROR(m_node->get_logger(),
"Could not initialize the GetPosition service");
169 m_getVelocitySrv = m_node->create_service<yarp_control_msgs::srv::GetVelocity>(m_getVelocitySrvName,
170 std::bind(&ControlBoard_nws_ros2::getVelocityCallback,
171 this,std::placeholders::_1,std::placeholders::_2,
172 std::placeholders::_3));
173 if(!m_getVelocitySrv){
175 RCLCPP_ERROR(m_node->get_logger(),
"Could not initialize the GetVelocity service");
179 m_setControlModesSrv = m_node->create_service<yarp_control_msgs::srv::SetControlModes>(m_setModesSrvName,
180 std::bind(&ControlBoard_nws_ros2::setControlModesCallback,
181 this,std::placeholders::_1,std::placeholders::_2,
182 std::placeholders::_3));
183 if(!m_setControlModesSrv){
185 RCLCPP_ERROR(m_node->get_logger(),
"Could not initialize the SetControlModes service");
189 m_getAvailableModesSrv = m_node->create_service<yarp_control_msgs::srv::GetAvailableControlModes>(m_getAvailableModesSrvName,
190 std::bind(&ControlBoard_nws_ros2::getAvailableModesCallback,
191 this,std::placeholders::_1,std::placeholders::_2,
192 std::placeholders::_3));
193 if(!m_getAvailableModesSrv){
195 RCLCPP_ERROR(m_node->get_logger(),
"Could not initialize the GetAvailableModes service");
199 m_getJointsNamesSrv = m_node->create_service<yarp_control_msgs::srv::GetJointsNames>(m_getJointsNamesSrvName,
200 std::bind(&ControlBoard_nws_ros2::getJointsNamesCallback,
201 this,std::placeholders::_1,std::placeholders::_2,
202 std::placeholders::_3));
203 if(!m_getJointsNamesSrv){
205 RCLCPP_ERROR(m_node->get_logger(),
"Could not initialize the GetJointsNames service");
213 RCLCPP_ERROR(m_node->get_logger(),
"Could not initialize the GetJointsNames service");
219 for(
size_t i=0; i<m_subdevice_joints; i++){
221 yCError(
CONTROLBOARD_ROS2) <<
"Error retrieving axis" << i <<
"name. For this device to work, every joint needs a name";
237 m_subdevice_ptr = driver;
239 m_subdevice_ptr->
view(m_iPositionControl);
240 if (!m_iPositionControl) {
244 m_subdevice_ptr->
view(m_iPositionDirect);
245 if (!m_iPositionDirect) {
249 m_subdevice_ptr->
view(m_iVelocityControl);
250 if (!m_iVelocityControl) {
254 m_subdevice_ptr->
view(m_iControlMode);
255 if (!m_iControlMode) {
259 m_subdevice_ptr->
view(m_iEncodersTimed);
260 if (!m_iEncodersTimed) {
265 m_subdevice_ptr->
view(m_iTorqueControl);
266 if (!m_iTorqueControl) {
270 m_subdevice_ptr->
view(m_iAxisInfo);
286 m_subdevice_joints =
static_cast<size_t>(
tmp_axes);
287 m_times.
resize(m_subdevice_joints);
288 m_ros_struct.name.resize(m_subdevice_joints);
289 m_ros_struct.position.resize(m_subdevice_joints);
290 m_ros_struct.velocity.resize(m_subdevice_joints);
291 m_ros_struct.effort.resize(m_subdevice_joints);
293 if (!updateAxisName()) {
301void ControlBoard_nws_ros2::closeDevice()
303 m_subdevice_ptr =
nullptr;
304 m_subdevice_joints = 0;
309 m_iPositionControl =
nullptr;
310 m_iEncodersTimed =
nullptr;
311 m_iTorqueControl =
nullptr;
312 m_iAxisInfo =
nullptr;
317 if (!setDevice(poly)) {
334 RCLCPP_ERROR(m_node->get_logger(),
"Error initializing the ROS2 control related topics and services");
340 if(!m_spinner->
start()){
360bool ControlBoard_nws_ros2::updateAxisName()
367 std::vector<std::string> tmpVect;
368 for (
size_t i = 0; i < m_subdevice_joints; i++) {
375 tmpVect.emplace_back(
tmp);
380 m_jointNames = tmpVect;
396 if (m_iTorqueControl) {
402 m_time.
update(std::accumulate(m_times.
begin(), m_times.
end(), 0.0) / m_subdevice_joints);
407 for (
size_t i = 0; i < m_subdevice_joints; i++) {
415 m_ros_struct.name = m_jointNames;
427 m_publisher->publish(m_ros_struct);
double convertDegreesToRadians(double degrees)
bool parseParams(const yarp::os::Searchable &config) override
Parse the DeviceDriver parameters.
bool open(yarp::os::Searchable &prop) override
Open the DeviceDriver.
void run() override
Loop function.
bool attach(yarp::dev::PolyDriver *poly) override
Attach to another object.
bool detach() override
Detach the object (you must have first called attach).
bool close() override
Close the DeviceDriver.
static rclcpp::Node::SharedPtr createNode(std::string name)
Interface implemented by all device drivers.
bool view(T *&x)
Get an interface to the device driver.
virtual bool getAxisName(int axis, std::string &name)=0
virtual bool getJointType(int axis, yarp::dev::JointTypeEnum &type)
virtual bool getEncodersTimed(double *encs, double *time)=0
Read the instantaneous acceleration of all axes.
virtual bool getAxes(int *ax)=0
Get the number of controlled axes.
virtual bool getEncoderSpeeds(double *spds)=0
Read the instantaneous speed of all axes.
virtual bool getTorques(double *t)=0
Get the value of the torque for all joints (this is the feedback if you have torque sensors).
A container for a device driver.
A mini-server for performing network communication in the background.
An abstraction for a periodic thread.
bool setPeriod(double period)
Set the (new) period of the thread.
bool isRunning() const
Returns true when the thread is started, false otherwise.
bool start()
Call this to start the thread.
void stop()
Call this to stop the thread, this call blocks until the thread is terminated (and releaseThread() ca...
A base class for nested structures that can be searched.
An abstraction for a time stamp and/or sequence number.
void update()
Set the timestamp to the current time, and increment the sequence number (wrapping to 0 if the sequen...
bool stop()
Stop the thread.
bool isRunning()
Returns true if the thread is running (Thread::start has been called successfully and the thread has ...
bool start()
Start the new thread running.
void resize(size_t size) override
Resize the vector.
iterator begin() noexcept
Returns an iterator to the beginning of the VectorOf.
T * data()
Return a pointer to the first element of the vector.
iterator end() noexcept
Returns an iterator to the end of the VectorOf.
#define yCError(component,...)
#define yCAssert(component, x)
#define yCWarning(component,...)
#define YARP_LOG_COMPONENT(name,...)
For streams capable of holding different kinds of content, check what they actually have.
@ VOCAB_JOINTTYPE_REVOLUTE
An interface to the operating system, including Port based communication.
The main, catch-all namespace for YARP.