YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
ControlBoard_nws_ros.h
Go to the documentation of this file.
1/*
2 * SPDX-FileCopyrightText: 2006-2023 Istituto Italiano di Tecnologia (IIT)
3 * SPDX-License-Identifier: BSD-3-Clause
4 */
5
6#ifndef YARP_DEV_CONTROLBOARD_NWS_ROS_H
7#define YARP_DEV_CONTROLBOARD_NWS_ROS_H
8
12
16#include <yarp/dev/IAxisInfo.h>
17
18#include <yarp/os/Stamp.h>
19#include <yarp/sig/Vector.h>
20
21#include <string>
22#include <vector>
23
24#include <yarp/os/Node.h>
25#include <yarp/os/Publisher.h>
26#include <yarp/rosmsg/sensor_msgs/JointState.h>
27
28
50{
51private:
52 yarp::rosmsg::sensor_msgs::JointState ros_struct;
53
54 yarp::sig::Vector times; // time for each joint
55
56 std::vector<std::string> jointNames; // name of the joints
57 std::string nodeName; // name of the rosNode
58 std::string topicName; // name of the rosTopic
59
60 yarp::os::Node* node; // ROS node
61 std::uint32_t counter {0}; // incremental counter in the ROS message
62
63 yarp::os::PortWriterBuffer<yarp::rosmsg::sensor_msgs::JointState> outputState_buffer; // Buffer associated to the ROS topic
64 yarp::os::Publisher<yarp::rosmsg::sensor_msgs::JointState> publisherPort; // Dedicated ROS topic publisher
65
66 static constexpr double default_period = 0.02; // s
67 double period {default_period};
68
69 yarp::os::Stamp time; // envelope to attach to the state port
70
71 yarp::dev::DeviceDriver* m_attached_device_ptr{nullptr};
72 size_t subdevice_joints {0};
73
74 yarp::dev::IPositionControl* iPositionControl{nullptr};
75 yarp::dev::IEncodersTimed* iEncodersTimed{nullptr};
76 yarp::dev::ITorqueControl* iTorqueControl{nullptr};
77 yarp::dev::IAxisInfo* iAxisInfo{nullptr};
78
79 bool setDevice(yarp::dev::DeviceDriver* device);
80
81 void closeDevice();
82 void closePorts();
83 bool updateAxisName();
84
85public:
91 ~ControlBoard_nws_ros() override = default;
92
93 // yarp::dev::DeviceDriver
94 bool close() override;
95 bool open(yarp::os::Searchable& prop) override;
96
97 // yarp::dev::WrapperSingle
98 bool attach(yarp::dev::PolyDriver* poly) override;
99 bool detach() override;
100
101 // yarp::os::PeriodicThread
102 void run() override;
103};
104
105#endif // YARP_DEV_CONTROLBOARD_NWS_ROS_H
constexpr double default_period
define control board standard interfaces
contains the definition of a Vector type
controlBoard_nws_ros: A controlBoard network wrapper server for ROS.
ControlBoard_nws_ros & operator=(const ControlBoard_nws_ros &)=delete
bool attach(yarp::dev::PolyDriver *poly) override
Attach to another object.
void run() override
Loop function.
bool close() override
Close the DeviceDriver.
bool open(yarp::os::Searchable &prop) override
Open the DeviceDriver.
ControlBoard_nws_ros(ControlBoard_nws_ros &&)=delete
bool detach() override
Detach the object (you must have first called attach).
ControlBoard_nws_ros(const ControlBoard_nws_ros &)=delete
ControlBoard_nws_ros & operator=(ControlBoard_nws_ros &&)=delete
~ControlBoard_nws_ros() override=default
Interface implemented by all device drivers.
Interface for getting information about specific axes, if available.
Definition IAxisInfo.h:36
Control board, extend encoder interface with timestamps.
Interface for a generic control board device implementing position control.
Interface for control boards implementing torque control.
A container for a device driver.
Definition PolyDriver.h:23
Helper interface for an object that can wrap/or "attach" to a single other device.
A mini-server for performing network communication in the background.
The Node class.
Definition Node.h:23
An abstraction for a periodic thread.
A base class for nested structures that can be searched.
Definition Searchable.h:31
An abstraction for a time stamp and/or sequence number.
Definition Stamp.h:21