14#include <yarp/rosmsg/impl/yarpRosHelper.h>
32void ControlBoard_nws_ros::closePorts()
35 publisherPort.
close();
61 if (prop.
check(
"period")) {
73 period = default_period;
77 if (!config.
check(
"node_name")) {
81 nodeName = config.
find(
"node_name").asString();
82 if(nodeName[0] !=
'/'){
88 if (!config.
check(
"topic_name")) {
92 topicName = config.
find(
"topic_name").asString();
93 if(topicName[0] !=
'/'){
100 if (!publisherPort.
topic(topicName)) {
113 m_attached_device_ptr = driver;
115 m_attached_device_ptr->
view(iPositionControl);
116 if (!iPositionControl) {
117 yCError(
CONTROLBOARD,
"<%s - %s>: IPositionControl interface was not found in attached device. Quitting", nodeName.c_str(), topicName.c_str());
121 m_attached_device_ptr->
view(iEncodersTimed);
122 if (!iEncodersTimed) {
123 yCError(
CONTROLBOARD,
"<%s - %s>: IEncodersTimed interface was not found in attached device. Quitting", nodeName.c_str(), topicName.c_str());
127 m_attached_device_ptr->
view(iTorqueControl);
128 if (!iTorqueControl) {
129 yCWarning(
CONTROLBOARD,
"<%s - %s>: ITorqueControl interface was not found in attached device.", nodeName.c_str(), topicName.c_str());
132 m_attached_device_ptr->
view(iAxisInfo);
134 yCError(
CONTROLBOARD,
"<%s - %s>: IAxisInfo interface was not found in attached device. Quitting", nodeName.c_str(), topicName.c_str());
141 yCError(
CONTROLBOARD,
"<%s - %s>: Failed to get axes number for attached device ", nodeName.c_str(), topicName.c_str());
145 yCError(
CONTROLBOARD,
"<%s - %s>: attached device has an invalid number of joints (%d)", nodeName.c_str(), topicName.c_str(),
tmp_axes);
148 subdevice_joints =
static_cast<size_t>(
tmp_axes);
149 times.
resize(subdevice_joints);
150 ros_struct.name.resize(subdevice_joints);
151 ros_struct.position.resize(subdevice_joints);
152 ros_struct.velocity.resize(subdevice_joints);
153 ros_struct.effort.resize(subdevice_joints);
155 if (!updateAxisName()) {
163void ControlBoard_nws_ros::closeDevice()
165 m_attached_device_ptr =
nullptr;
166 subdevice_joints = 0;
171 iPositionControl =
nullptr;
172 iEncodersTimed =
nullptr;
173 iTorqueControl =
nullptr;
179 if (!setDevice(poly)) {
205bool ControlBoard_nws_ros::updateAxisName()
212 std::vector<std::string> tmpVect;
213 for (
size_t i = 0;
i < subdevice_joints;
i++) {
220 tmpVect.emplace_back(
tmp);
225 jointNames = tmpVect;
242 if (iTorqueControl) {
248 time.
update(std::accumulate(times.
begin(), times.
end(), 0.0) / subdevice_joints);
253 for (
size_t i = 0;
i < subdevice_joints;
i++) {
261 ros_struct.name = jointNames;
263 ros_struct.header.seq = counter++;
266 publisherPort.
write(ros_struct);
const yarp::os::LogComponent & CONTROLBOARD()
constexpr double default_period
double convertDegreesToRadians(double degrees)
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.
bool detach() override
Detach the object (you must have first called attach).
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 getEncoderSpeeds(double *spds)=0
Read the instantaneous speed of all axes.
virtual bool getAxes(int *ax)=0
Get the number of controlled 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 class for storing options and configuration information.
Value & find(const std::string &key) const override
Gets a value corresponding to a given keyword.
void fromString(const std::string &txt, bool wipe=true)
Interprets a string as a list of properties.
bool check(const std::string &key) const override
Check if there exists a property of the given name.
void close() override
Stop port activity.
bool topic(const std::string &name)
Set topic to publish to.
void interrupt() override
Interrupt any current reads or writes attached to the port.
void write(bool forceStrict=false)
Write the current object being returned by Publisher::prepare.
A base class for nested structures that can be searched.
virtual bool check(const std::string &key) const =0
Check if there exists a property of the given name.
virtual std::string toString() const =0
Return a standard text representation of the content of the object.
virtual Value & find(const std::string &key) const =0
Gets a value corresponding to a given keyword.
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...
virtual yarp::conf::float64_t asFloat64() const
Get 64-bit floating point value.
virtual bool isFloat64() const
Checks if value is a 64-bit floating point number.
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 yCInfo(component,...)
#define yCError(component,...)
#define yCAssert(component, x)
#define yCWarning(component,...)
#define yCDebug(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.