YARP
Yet Another Robot Platform
AnalogWrapper.h
Go to the documentation of this file.
1
/*
2
* Copyright (C) 2006-2020 Istituto Italiano di Tecnologia (IIT)
3
* All rights reserved.
4
*
5
* This software may be modified and distributed under the terms of the
6
* BSD-3-Clause license. See the accompanying LICENSE file for details.
7
*/
8
9
#ifndef YARP_DEV_ANALOGWRAPPER_ANALOGWRAPPER_H
10
#define YARP_DEV_ANALOGWRAPPER_ANALOGWRAPPER_H
11
12
//#include <list>
13
#include <vector>
14
#include <iostream>
15
#include <string>
16
#include <sstream>
17
18
#include <
yarp/os/Network.h
>
19
#include <
yarp/os/Port.h
>
20
#include <
yarp/os/BufferedPort.h
>
21
#include <
yarp/os/Bottle.h
>
22
#include <
yarp/os/Time.h
>
23
#include <
yarp/os/Property.h
>
24
25
#include <
yarp/os/PeriodicThread.h
>
26
#include <
yarp/os/BufferedPort.h
>
27
#include <
yarp/os/Stamp.h
>
28
29
#include <
yarp/sig/Vector.h
>
30
31
#include <
yarp/dev/IAnalogSensor.h
>
32
#include <
yarp/dev/PolyDriver.h
>
33
#include <
yarp/dev/DeviceDriver.h
>
34
#include <
yarp/dev/IMultipleWrapper.h
>
35
#include <
yarp/dev/api.h
>
36
37
38
// ROS state publisher
39
#include <
yarp/os/Node.h
>
40
#include <
yarp/os/Publisher.h
>
41
#include <
yarp/rosmsg/geometry_msgs/WrenchStamped.h
>
42
#include <
yarp/rosmsg/sensor_msgs/JointState.h
>
43
#include <
yarp/rosmsg/impl/yarpRosHelper.h
>
44
45
#define DEFAULT_THREAD_PERIOD 20 //ms
46
47
class
AnalogServerHandler
;
48
class
AnalogPortEntry
;
49
187
class
AnalogWrapper
:
188
public
yarp::os::PeriodicThread
,
189
public
yarp::dev::DeviceDriver
,
190
public
yarp::dev::IMultipleWrapper
191
{
192
public
:
193
AnalogWrapper
();
194
195
AnalogWrapper
(
const
AnalogWrapper
&) =
delete
;
196
AnalogWrapper
(
AnalogWrapper
&&) =
delete
;
197
AnalogWrapper
&
operator=
(
const
AnalogWrapper
&) =
delete
;
198
AnalogWrapper
&
operator=
(
AnalogWrapper
&&) =
delete
;
199
200
~AnalogWrapper
()
override
;
201
202
bool
open
(
yarp::os::Searchable
¶ms)
override
;
203
bool
close
()
override
;
204
yarp::os::Bottle
getOptions
();
205
206
void
setId
(
const
std::string &
id
);
207
std::string
getId
();
208
212
bool
attachAll
(
const
yarp::dev::PolyDriverList
&p)
override
;
213
bool
detachAll
()
override
;
214
215
void
attach
(
yarp::dev::IAnalogSensor
*s);
216
void
detach
();
217
218
bool
threadInit
()
override
;
219
void
threadRelease
()
override
;
220
void
run
()
override
;
221
222
private
:
223
std::string streamingPortName;
224
std::string rpcPortName;
225
yarp::dev::IAnalogSensor
*analogSensor_p{
nullptr
};
// the analog sensor to read from
226
std::vector<AnalogPortEntry> analogPorts;
// the list of output ports
227
std::vector<AnalogServerHandler*> handlers;
// the list of rpc port handlers
228
yarp::os::Stamp
lastStateStamp;
// the last reading time stamp
229
yarp::sig::Vector
lastDataRead;
// the last vector of data read from the attached IAnalogSensor
230
int
_rate{
DEFAULT_THREAD_PERIOD
};
231
std::string sensorId;
232
233
// ROS state publisher
234
ROSTopicUsageType
useROS{
ROS_disabled
};
// decide if open ROS topic or not
235
std::vector<std::string> frame_idVec;
// name of the reference frame the measures are referred to
236
std::vector<std::string> ros_joint_names;
237
std::string rosMsgType;
// ros message type
238
std::string rosNodeName{
""
};
// name of the rosNode
239
std::vector<std::string> rosTopicNamesVec;
// names of the rosTopics
240
yarp::os::Node
* rosNode{
nullptr
};
// add a ROS node
241
std::vector<yarp::os::NetUint32> rosMsgCounterVec;
// incremental counter in the ROS message
242
int
rosOffset{0};
// offset to be ignored from the analog sensor data
243
int
rosPadding{0};
// padding to be ignored from the analog sensor data
244
245
// TODO: in the future, in order to support multiple ROS msgs this should be a pointer allocated dynamically depending on the msg maybe (??)
246
// yarp::os::PortWriterBuffer<yarp::rosmsg::geometry_msgs::WrenchStamped> rosOutputWrench_buffer; // Buffer associated to the ROS topic
247
std::vector<yarp::os::Publisher<yarp::rosmsg::geometry_msgs::WrenchStamped>> rosPublisherWrenchPortVec;
// Dedicated ROS topic publisher
248
249
//yarp::os::PortWriterBuffer<yarp::rosmsg::sensor_msgs::JointState> rosOutputJoint_buffer; // Buffer associated to the ROS topic
250
yarp::os::Publisher<yarp::rosmsg::sensor_msgs::JointState>
rosPublisherJointPort;
// Dedicated ROS topic publisher
251
252
253
bool
ownDevices{
false
};
254
// Open the wrapper only, the attach method needs to be called before using it
255
bool
openDeferredAttach(
yarp::os::Searchable
&prop);
256
257
// For the simulator, if a subdevice parameter is given to the wrapper, it will
258
// open it and attach to it immediately.
259
yarp::dev::PolyDriver
*subDeviceOwned{
nullptr
};
260
bool
openAndAttachSubDevice(
yarp::os::Searchable
&prop);
261
262
bool
checkROSParams(
yarp::os::Searchable
&config);
263
bool
initialize_ROS();
264
bool
initialize_YARP(
yarp::os::Searchable
&config);
265
266
void
setHandlers();
267
void
removeHandlers();
268
269
// Function used when there is only one output port
270
bool
createPort(
const
char
* name,
int
rate=20);
271
// Function used when one or more output ports are specified
272
bool
createPorts(
const
std::vector<AnalogPortEntry>& _analogPorts,
int
rate=20);
273
bool
checkForDeprecatedParams(
yarp::os::Searchable
¶ms);
274
};
275
276
#endif // YARP_DEV_ANALOGWRAPPER_ANALOGWRAPPER_H
yarp::os::Bottle
A simple collection of objects that can be described and transmitted in a portable way.
Definition:
Bottle.h:73
AnalogWrapper::AnalogWrapper
AnalogWrapper(AnalogWrapper &&)=delete
Network.h
JointState.h
yarp::os::Searchable
A base class for nested structures that can be searched.
Definition:
Searchable.h:69
Vector.h
contains the definition of a Vector type
WrenchStamped.h
AnalogWrapper::AnalogWrapper
AnalogWrapper()
Definition:
AnalogWrapper.cpp:216
Port.h
yarp::dev::DeviceDriver
Interface implemented by all device drivers.
Definition:
DeviceDriver.h:38
AnalogWrapper::~AnalogWrapper
~AnalogWrapper() override
Definition:
AnalogWrapper.cpp:228
AnalogWrapper::getOptions
yarp::os::Bottle getOptions()
AnalogWrapper::threadInit
bool threadInit() override
Initialization method.
Definition:
AnalogWrapper.cpp:381
yarp::os::Publisher< yarp::rosmsg::sensor_msgs::JointState >
yarp::dev::PolyDriverList
Definition:
PolyDriverList.h:22
AnalogWrapper::operator=
AnalogWrapper & operator=(AnalogWrapper &&)=delete
yarpRosHelper.h
AnalogWrapper::detachAll
bool detachAll() override
Detach the object (you must have first called attach).
Definition:
AnalogWrapper.cpp:344
yarp::sig::VectorOf
Provides:
Definition:
Vector.h:122
AnalogWrapper::attachAll
bool attachAll(const yarp::dev::PolyDriverList &p) override
Specify which analog sensor this thread has to read from.
Definition:
AnalogWrapper.cpp:315
AnalogWrapper::close
bool close() override
Close the DeviceDriver.
Definition:
AnalogWrapper.cpp:991
Property.h
AnalogWrapper::setId
void setId(const std::string &id)
Definition:
AnalogWrapper.cpp:395
ROSTopicUsageType
ROSTopicUsageType
Definition:
yarpRosHelper.h:19
PolyDriver.h
Stamp.h
AnalogWrapper::detach
void detach()
Definition:
AnalogWrapper.cpp:371
yarp::dev::PolyDriver
A container for a device driver.
Definition:
PolyDriver.h:27
ROS_disabled
@ ROS_disabled
Definition:
yarpRosHelper.h:21
Node.h
AnalogWrapper::threadRelease
void threadRelease() override
Release method.
Definition:
AnalogWrapper.cpp:866
AnalogWrapper::run
void run() override
Loop function.
Definition:
AnalogWrapper.cpp:875
AnalogWrapper::AnalogWrapper
AnalogWrapper(const AnalogWrapper &)=delete
AnalogPortEntry
A yarp port that output data read from an analog sensor.
Definition:
AnalogWrapper.cpp:52
yarp::dev::IAnalogSensor
A generic interface to sensors (gyro, a/d converters).
Definition:
IAnalogSensor.h:31
yarp::os::Node
The Node class.
Definition:
Node.h:27
AnalogWrapper::getId
std::string getId()
Definition:
AnalogWrapper.cpp:400
BufferedPort.h
IMultipleWrapper.h
AnalogWrapper::operator=
AnalogWrapper & operator=(const AnalogWrapper &)=delete
yarp::os::PeriodicThread
An abstraction for a periodic thread.
Definition:
PeriodicThread.h:25
PeriodicThread.h
AnalogWrapper::attach
void attach(yarp::dev::IAnalogSensor *s)
Definition:
AnalogWrapper.cpp:359
yarp::os::Stamp
An abstraction for a time stamp and/or sequence number.
Definition:
Stamp.h:25
Publisher.h
AnalogWrapper::open
bool open(yarp::os::Searchable ¶ms) override
Open the DeviceDriver.
Definition:
AnalogWrapper.cpp:695
DEFAULT_THREAD_PERIOD
#define DEFAULT_THREAD_PERIOD
Definition:
AnalogWrapper.h:45
yarp::dev::IMultipleWrapper
Interface for an object that can wrap/attach to to another.
Definition:
IMultipleWrapper.h:30
AnalogServerHandler
Handler of the rpc port related to an analog sensor.
Definition:
AnalogWrapper.cpp:30
Time.h
AnalogWrapper
analogServer: Device that expose an AnalogSensor (using the IAnalogSensor interface) on the YARP or R...
Definition:
AnalogWrapper.h:191
IAnalogSensor.h
analog sensor interface
api.h
Bottle.h
DeviceDriver.h
YARP
3.4.100+20201223.2+gitb8ea4d712
src
devices
AnalogWrapper
AnalogWrapper.h
Generated on Sun Jan 3 2021 02:46:22 for YARP by
1.8.20