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>
17 #include <yarp/os/BufferedPort.h>
18 #include <yarp/os/Bottle.h>
19 #include <yarp/os/Time.h>
20 #include <yarp/os/Property.h>
21 
22 #include <yarp/os/PeriodicThread.h>
23 #include <yarp/os/BufferedPort.h>
24 #include <yarp/os/Stamp.h>
25 
26 #include <yarp/sig/Vector.h>
27 
28 #include <yarp/dev/IAnalogSensor.h>
29 #include <yarp/dev/PolyDriver.h>
30 #include <yarp/dev/DeviceDriver.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 
45 class AnalogPortEntry;
46 
188 {
189 public:
190  AnalogWrapper();
191 
192  AnalogWrapper(const AnalogWrapper&) = delete;
196 
197  ~AnalogWrapper() override;
198 
199  bool open(yarp::os::Searchable &params) override;
200  bool close() override;
202 
203  void setId(const std::string &id);
204  std::string getId();
205 
209  bool attachAll(const yarp::dev::PolyDriverList &p) override;
210  bool detachAll() override;
211 
213  void detach();
214 
215  bool threadInit() override;
216  void threadRelease() override;
217  void run() override;
218 
219 private:
220  std::string streamingPortName;
221  std::string rpcPortName;
222  yarp::dev::IAnalogSensor *analogSensor_p{nullptr}; // the analog sensor to read from
223  std::vector<AnalogPortEntry> analogPorts; // the list of output ports
224  std::vector<AnalogServerHandler*> handlers; // the list of rpc port handlers
225  yarp::os::Stamp lastStateStamp; // the last reading time stamp
226  yarp::sig::Vector lastDataRead; // the last vector of data read from the attached IAnalogSensor
227  int _rate{DEFAULT_THREAD_PERIOD};
228  std::string sensorId;
229 
230  // ROS state publisher
231  ROSTopicUsageType useROS{ROS_disabled}; // decide if open ROS topic or not
232  std::vector<std::string> frame_idVec; // name of the reference frame the measures are referred to
233  std::vector<std::string> ros_joint_names;
234  std::string rosMsgType; // ros message type
235  std::string rosNodeName{""}; // name of the rosNode
236  std::vector<std::string> rosTopicNamesVec; // names of the rosTopics
237  yarp::os::Node* rosNode{nullptr}; // add a ROS node
238  std::vector<yarp::os::NetUint32> rosMsgCounterVec; // incremental counter in the ROS message
239  int rosOffset{0}; // offset to be ignored from the analog sensor data
240  int rosPadding{0}; // padding to be ignored from the analog sensor data
241 
242  // TODO: in the future, in order to support multiple ROS msgs this should be a pointer allocated dynamically depending on the msg maybe (??)
243  // yarp::os::PortWriterBuffer<yarp::rosmsg::geometry_msgs::WrenchStamped> rosOutputWrench_buffer; // Buffer associated to the ROS topic
244  std::vector<yarp::os::Publisher<yarp::rosmsg::geometry_msgs::WrenchStamped>> rosPublisherWrenchPortVec; // Dedicated ROS topic publisher
245 
246  //yarp::os::PortWriterBuffer<yarp::rosmsg::sensor_msgs::JointState> rosOutputJoint_buffer; // Buffer associated to the ROS topic
247  yarp::os::Publisher<yarp::rosmsg::sensor_msgs::JointState> rosPublisherJointPort; // Dedicated ROS topic publisher
248 
249 
250  bool ownDevices{false};
251  // Open the wrapper only, the attach method needs to be called before using it
252  bool openDeferredAttach(yarp::os::Searchable &prop);
253 
254  // For the simulator, if a subdevice parameter is given to the wrapper, it will
255  // open it and attach to it immediately.
256  yarp::dev::PolyDriver *subDeviceOwned{nullptr};
257  bool openAndAttachSubDevice(yarp::os::Searchable &prop);
258 
259  bool checkROSParams(yarp::os::Searchable &config);
260  bool initialize_ROS();
261  bool initialize_YARP(yarp::os::Searchable &config);
262 
263  void setHandlers();
264  void removeHandlers();
265 
266  // Function used when there is only one output port
267  bool createPort(const char* name, int rate=20);
268  // Function used when one or more output ports are specified
269  bool createPorts(const std::vector<AnalogPortEntry>& _analogPorts, int rate=20);
270  bool checkForDeprecatedParams(yarp::os::Searchable &params);
271 };
272 
273 #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...
AnalogWrapper & operator=(const AnalogWrapper &)=delete
void threadRelease() override
Release method.
void setId(const std::string &id)
void attach(yarp::dev::IAnalogSensor *s)
bool threadInit() override
Initialization method.
~AnalogWrapper() override
AnalogWrapper(AnalogWrapper &&)=delete
void run() override
Loop function.
AnalogWrapper & operator=(AnalogWrapper &&)=delete
bool open(yarp::os::Searchable &params) override
Open the DeviceDriver.
AnalogWrapper(const AnalogWrapper &)=delete
std::string getId()
bool close() override
Close the DeviceDriver.
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()
Interface implemented by all device drivers.
Definition: DeviceDriver.h:35
A generic interface to sensors (gyro, a/d converters).
Definition: IAnalogSensor.h:28
Interface for an object that can wrap/attach to to another.
A container for a device driver.
Definition: PolyDriver.h:24
A simple collection of objects that can be described and transmitted in a portable way.
Definition: Bottle.h:74
The Node class.
Definition: Node.h:24
An abstraction for a periodic thread.
A base class for nested structures that can be searched.
Definition: Searchable.h:66
An abstraction for a time stamp and/or sequence number.
Definition: Stamp.h:22
ROSTopicUsageType
Definition: yarpRosHelper.h:16
@ ROS_disabled
Definition: yarpRosHelper.h:18