YARP
Yet Another Robot Platform
AnalogWrapper.h
Go to the documentation of this file.
1/*
2 * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT)
3 * SPDX-License-Identifier: BSD-3-Clause
4 */
5
6#ifndef YARP_DEV_ANALOGWRAPPER_ANALOGWRAPPER_H
7#define YARP_DEV_ANALOGWRAPPER_ANALOGWRAPPER_H
8
9 //#include <list>
10#include <vector>
11#include <iostream>
12#include <string>
13#include <sstream>
14
15#include <yarp/os/Network.h>
16#include <yarp/os/Port.h>
18#include <yarp/os/Bottle.h>
19#include <yarp/os/Time.h>
20#include <yarp/os/Property.h>
21
24#include <yarp/os/Stamp.h>
25
26#include <yarp/sig/Vector.h>
27
29#include <yarp/dev/PolyDriver.h>
32#include <yarp/dev/api.h>
33
34
35// ROS state publisher
36#include <yarp/os/Node.h>
37#include <yarp/os/Publisher.h>
41
42#define DEFAULT_THREAD_PERIOD 20 //ms
43
45class AnalogPortEntry;
46
188{
189public:
191
192 AnalogWrapper(const AnalogWrapper&) = delete;
196
197 ~AnalogWrapper() override;
198
199 bool open(yarp::os::Searchable &params) override;
200 bool close() override;
202
206 bool attachAll(const yarp::dev::PolyDriverList &p) override;
207 bool detachAll() override;
208
210 void detach();
211
212 bool threadInit() override;
213 void threadRelease() override;
214 void run() override;
215
216private:
217 std::string streamingPortName;
218 std::string rpcPortName;
219 yarp::dev::IAnalogSensor *analogSensor_p{nullptr}; // the analog sensor to read from
220 std::vector<AnalogPortEntry> analogPorts; // the list of output ports
221 std::vector<AnalogServerHandler*> handlers; // the list of rpc port handlers
222 yarp::os::Stamp lastStateStamp; // the last reading time stamp
223 yarp::sig::Vector lastDataRead; // the last vector of data read from the attached IAnalogSensor
224 int _rate{DEFAULT_THREAD_PERIOD};
225 std::string sensorId;
226
227 // ROS state publisher
228 ROSTopicUsageType useROS{ROS_disabled}; // decide if open ROS topic or not
229 std::vector<std::string> frame_idVec; // name of the reference frame the measures are referred to
230 std::vector<std::string> ros_joint_names;
231 std::string rosMsgType; // ros message type
232 std::string rosNodeName{""}; // name of the rosNode
233 std::vector<std::string> rosTopicNamesVec; // names of the rosTopics
234 yarp::os::Node* rosNode{nullptr}; // add a ROS node
235 std::vector<yarp::os::NetUint32> rosMsgCounterVec; // incremental counter in the ROS message
236 int rosOffset{0}; // offset to be ignored from the analog sensor data
237 int rosPadding{0}; // padding to be ignored from the analog sensor data
238
239 // TODO: in the future, in order to support multiple ROS msgs this should be a pointer allocated dynamically depending on the msg maybe (??)
240 // yarp::os::PortWriterBuffer<yarp::rosmsg::geometry_msgs::WrenchStamped> rosOutputWrench_buffer; // Buffer associated to the ROS topic
241 std::vector<yarp::os::Publisher<yarp::rosmsg::geometry_msgs::WrenchStamped>> rosPublisherWrenchPortVec; // Dedicated ROS topic publisher
242
243 //yarp::os::PortWriterBuffer<yarp::rosmsg::sensor_msgs::JointState> rosOutputJoint_buffer; // Buffer associated to the ROS topic
244 yarp::os::Publisher<yarp::rosmsg::sensor_msgs::JointState> rosPublisherJointPort; // Dedicated ROS topic publisher
245
246
247 bool ownDevices{false};
248 // Open the wrapper only, the attach method needs to be called before using it
249 bool openDeferredAttach(yarp::os::Searchable &prop);
250
251 // For the simulator, if a subdevice parameter is given to the wrapper, it will
252 // open it and attach to it immediately.
253 yarp::dev::PolyDriver *subDeviceOwned{nullptr};
254 bool openAndAttachSubDevice(yarp::os::Searchable &prop);
255
256 bool checkROSParams(yarp::os::Searchable &config);
257 bool initialize_ROS();
258 bool initialize_YARP(yarp::os::Searchable &config);
259
260 void setHandlers();
261 void removeHandlers();
262
263 // Function used when there is only one output port
264 bool createPort(const char* name, int rate=20);
265 // Function used when one or more output ports are specified
266 bool createPorts(const std::vector<AnalogPortEntry>& _analogPorts, int rate=20);
267 bool checkForDeprecatedParams(yarp::os::Searchable &params);
268};
269
270#endif // YARP_DEV_ANALOGWRAPPER_ANALOGWRAPPER_H
#define DEFAULT_THREAD_PERIOD
Definition: AnalogWrapper.h:42
analog sensor interface
contains the definition of a Vector type
A yarp port that output data read from an analog sensor.
Handler of the rpc port related to an analog sensor.
analogServer deprecated: Device that expose an AnalogSensor (using the IAnalogSensor interface) on th...
void threadRelease() override
Release method.
void attach(yarp::dev::IAnalogSensor *s)
bool threadInit() override
Initialization method.
~AnalogWrapper() override
AnalogWrapper(AnalogWrapper &&)=delete
void run() override
Loop function.
bool open(yarp::os::Searchable &params) override
Open the DeviceDriver.
AnalogWrapper(const AnalogWrapper &)=delete
bool close() override
Close the DeviceDriver.
AnalogWrapper & operator=(AnalogWrapper &&)=delete
bool attachAll(const yarp::dev::PolyDriverList &p) override
Specify which analog sensor this thread has to read from.
bool detachAll() override
Detach the object (you must have first called attach).
yarp::os::Bottle getOptions()
AnalogWrapper & operator=(const AnalogWrapper &)=delete
Interface implemented by all device drivers.
Definition: DeviceDriver.h:30
A generic interface to sensors (gyro, a/d converters).
Definition: IAnalogSensor.h:27
Interface for an object that can wrap/attach to to another.
A container for a device driver.
Definition: PolyDriver.h:23
A simple collection of objects that can be described and transmitted in a portable way.
Definition: Bottle.h:64
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:63
An abstraction for a time stamp and/or sequence number.
Definition: Stamp.h:21
ROSTopicUsageType
Definition: yarpRosHelper.h:16
@ ROS_disabled
Definition: yarpRosHelper.h:18