6#ifndef YARP_DEV_CONTROLBOARD_NWS_ROS_H
7#define YARP_DEV_CONTROLBOARD_NWS_ROS_H
26#include <yarp/rosmsg/sensor_msgs/JointState.h>
52 yarp::rosmsg::sensor_msgs::JointState ros_struct;
56 std::vector<std::string> jointNames;
58 std::string topicName;
61 std::uint32_t counter {0};
66 static constexpr double default_period = 0.02;
72 size_t subdevice_joints {0};
83 bool updateAxisName();
94 bool close()
override;
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.
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.
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.
An abstraction for a periodic thread.
A base class for nested structures that can be searched.
An abstraction for a time stamp and/or sequence number.