88 const size_t msgsize=cmd.
size();
89 int ret=IAnalogSensor::AS_ERROR;
97 }
else if (msgsize > 2) {
99 Vector v(msgsize - offset);
100 for (
unsigned int i = 0; i < v.
size(); i++) {
131 bool ok=in.
read(connection);
151 if (returnToSender!=
nullptr) {
152 out.
write(*returnToSender);
192bool AnalogWrapper::createPort(
const char* name,
int rate)
194 analogSensor_p=
nullptr;
195 analogPorts.resize(1);
196 analogPorts[0].offset = 0;
197 analogPorts[0].length = -1;
198 analogPorts[0].port_name = std::string(name);
204bool AnalogWrapper::createPorts(
const std::vector<AnalogPortEntry>& _analogPorts,
int rate)
206 analogSensor_p=
nullptr;
207 this->analogPorts=_analogPorts;
217 frame_idVec.resize(1);
218 frame_idVec.at(0) =
"";
219 rosTopicNamesVec.resize(1);
220 rosTopicNamesVec.at(0) =
"";
221 rosMsgCounterVec.resize(1);
222 rosMsgCounterVec.at(0) = 0;
230 analogSensor_p =
nullptr;
233void AnalogWrapper::setHandlers()
235 for(
auto& analogPort : analogPorts)
237 std::string rpcPortName = analogPort.port_name;
238 rpcPortName +=
"/rpc:i";
240 handlers.push_back(ash);
244void AnalogWrapper::removeHandlers()
257bool AnalogWrapper::openAndAttachSubDevice(
Searchable &prop)
269 subDeviceOwned->
open(p);
271 if (!subDeviceOwned->
isValid())
277 subDeviceOwned->
view(analogSensor_p);
279 if (analogSensor_p ==
nullptr)
281 yCError(
ANALOGWRAPPER,
"Opening IAnalogSensor interface of AnalogWrapper subdevice... FAILED\n");
294 PeriodicThread::setPeriod(_rate / 1000.0);
295 return PeriodicThread::start();
302 if ((subDeviceOwned !=
nullptr) || (ownDevices ==
true)) {
320 if (analog2attach.
size() != 1)
330 Idevice2attach->
view(analogSensor_p);
333 if(
nullptr == analogSensor_p)
339 PeriodicThread::setPeriod(_rate / 1000.0);
340 return PeriodicThread::start();
350 analogSensor_p =
nullptr;
351 for(
unsigned int i=0; i<analogPorts.size(); i++)
353 if (handlers[i] !=
nullptr) {
354 handlers[i]->setInterface(analogSensor_p);
363 for(
unsigned int i=0; i<analogPorts.size(); i++)
365 handlers[i]->setInterface(analogSensor_p);
375 analogSensor_p =
nullptr;
376 for(
unsigned int i=0; i<analogPorts.size(); i++)
378 handlers[i]->setInterface(analogSensor_p);
384 for(
auto& analogPort : analogPorts)
387 if (!analogPort.port.open(analogPort.port_name))
396bool AnalogWrapper::checkROSParams(
Searchable &config)
399 if(!config.
check(
"ROS") )
402 yCInfo(
ANALOGWRAPPER) <<
"No ROS group found in config file ... skipping ROS initialization.";
417 if(!rosGroup.
check(
"useROS"))
419 yCError(
ANALOGWRAPPER) << sensorId <<
" cannot find useROS parameter, mandatory when using ROS message. \n \
420 Allowed values are true, false, ROS_only";
424 std::string ros_use_type = rosGroup.
find(
"useROS").
asString();
425 if(ros_use_type ==
"false")
431 else if(ros_use_type ==
"true")
436 else if(ros_use_type ==
"only")
443 yCInfo(
ANALOGWRAPPER) << sensorId <<
"useROS parameter is set to unvalid value ('" << ros_use_type <<
"'), supported values are 'true', 'false', 'only'";
449 if(!rosGroup.
check(
"ROS_nodeName"))
451 yCError(
ANALOGWRAPPER) << sensorId <<
" cannot find ROS_nodeName parameter, mandatory when using ROS message";
459 if(!rosGroup.
check(
"ROS_topicName"))
461 yCError(
ANALOGWRAPPER) << sensorId <<
" cannot find ROS_topicName parameter, mandatory when using ROS message";
468 rosTopicNamesVec.at(0) = rosGroup.
find(
"ROS_topicName").
asString();
472 else if(rosGroup.
find(
"ROS_topicName").
isList())
477 rosTopicNamesVec.resize(rosTopicNamesBottle->
size());
478 for(
size_t i = 0; i < rosTopicNamesBottle->
size(); i++)
480 rosTopicNamesVec.at(i) = rosTopicNamesBottle->
get(i).
asString();
484 rosMsgCounterVec.resize(rosTopicNamesVec.size());
488 if (!rosGroup.
check(
"ROS_msgType"))
490 yCError(
ANALOGWRAPPER) << sensorId <<
" cannot find ROS_msgType parameter, mandatory when using ROS message";
497 if (rosMsgType ==
"geometry_msgs/WrenchStamped")
500 if (!rosGroup.
check(
"frame_id"))
502 yCError(
ANALOGWRAPPER) << sensorId <<
" cannot find frame_id parameter, mandatory when using ROS message";
509 frame_idVec.at(0) = rosGroup.
find(
"frame_id").
asString();
517 if(frame_idBottle->
size() != rosTopicNamesVec.size())
519 yCError(
ANALOGWRAPPER,
"AnalogWrapper: mismatch between the number of ros topics and frame_ids");
525 frame_idVec.resize(frame_idBottle->
size());
526 for(
size_t i = 0; i < frame_idBottle->
size(); i++)
528 frame_idVec.at(i) = frame_idBottle->
get(i).
asString();
532 if(!rosGroup.
check(
"rosOffset"))
534 yCWarning(
ANALOGWRAPPER) << sensorId <<
"cannot find rosOffset parameter, using the default offset 0 while reading analog sensor data";
543 if(!rosGroup.
check(
"rosPadding"))
545 yCWarning(
ANALOGWRAPPER) << sensorId <<
"cannot find rosPadding parameter, using the default padding 0 while reading analog sensor data";
554 else if (rosMsgType ==
"sensor_msgs/JointState")
556 std::string jointName;
558 bool oldParam =
false;
559 bool newParam =
false;
561 if(rosGroup.
check(
"joint_names"))
564 jointName =
"joint_names";
565 yCWarning(
ANALOGWRAPPER) << sensorId <<
" using DEPRECATED 'joint_names' parameter. Please use 'jointNames' instead.";
568 if(rosGroup.
check(
"jointNames"))
571 jointName =
"jointNames";
574 if(!oldParam && !newParam)
576 yCError(
ANALOGWRAPPER) << sensorId <<
" missing 'jointNames' parameter needed when broadcasting 'sensor_msgs/JointState' message type";
581 if(oldParam && newParam)
583 yCError(
ANALOGWRAPPER) << sensorId <<
" found both DEPRECATED 'joint_names' and new 'jointNames' parameters. Please remove the old 'joint_names' from your config file.";
596 int joint_names_size = jnam.
size()-1;
597 for (
int i = 0; i < joint_names_size; i++)
599 ros_joint_names.push_back(jnam.
get(i+1).
asString());
611bool AnalogWrapper::initialize_ROS()
613 bool success =
false;
621 if(rosNode ==
nullptr)
623 yCError(
ANALOGWRAPPER) <<
" opening " << rosNodeName <<
" Node, check your yarp-ROS network configuration\n";
628 if (rosMsgType ==
"geometry_msgs/WrenchStamped")
630 rosPublisherWrenchPortVec.resize(rosTopicNamesVec.size());
632 for(
size_t i = 0; i < rosTopicNamesVec.size(); i++)
634 if(!rosPublisherWrenchPortVec.at(i).topic(rosTopicNamesVec.at(i)))
636 yCError(
ANALOGWRAPPER) <<
" opening " << rosTopicNamesVec.at(i) <<
" Topic, check your yarp-ROS network configuration\n";
642 else if (rosMsgType ==
"sensor_msgs/JointState")
644 if (!rosPublisherJointPort.
topic(rosTopicNamesVec.at(0)))
646 yCError(
ANALOGWRAPPER) <<
" opening " << rosTopicNamesVec.at(0) <<
" Topic, check your yarp-ROS network configuration\n";
656 yCInfo(
ANALOGWRAPPER) << sensorId <<
"ROS initialized successfully, node:" << rosNodeName <<
" and opened the following topics: ";
657 for(
size_t i = 0; i < rosTopicNamesVec.size(); i++)
673 yCError(
ANALOGWRAPPER) << sensorId <<
" ROS parameter are not correct, check your configuration file";
679 yCError(
ANALOGWRAPPER) << sensorId <<
" something went wrong with ROS configuration, we should never be here!!!";
690 yCWarning(
ANALOGWRAPPER) <<
"'MultipleAnalogSensorsRemapper`+`MultipleAnalogSensorsServer`, `PoseStampedRosPublisher`, `WrenchStampedRosPublisher`,`IMURosPublisher`,etc.";
691 yCWarning(
ANALOGWRAPPER) <<
"The old device is no longer supported, and it will be deprecated in YARP 3.7 and removed in YARP 4.";
698 if (!config.
check(
"period"))
700 yCError(
ANALOGWRAPPER) <<
"AnalogWrapper: missing 'period' parameter. Check you configuration file\n";
708 if (config.
check(
"deviceId"))
710 yCError(
ANALOGWRAPPER) <<
"AnalogWrapper: the parameter 'deviceId' has been removed, please use parameter 'name' instead. \n"
711 <<
"e.g. In the FT wrapper configuration files of your robot, replace '<param name=""deviceId""> left_arm </param>' \n"
712 <<
"with '/icub/left_arm/analog:o' ";
716 if (!config.
check(
"name"))
718 yCError(
ANALOGWRAPPER) <<
"AnalogWrapper: missing 'name' parameter. Check you configuration file; it must be like:\n"
719 " name: full name of the port, like /robotName/deviceId/sensorType:o";
727 if(!checkROSParams(config) )
729 yCError(
ANALOGWRAPPER) << sensorId <<
"ROS parameter are not correct, check your configuration file";
733 if(!initialize_YARP(config) )
739 if(!initialize_ROS() )
747 if(config.
check(
"subdevice"))
750 if(! openAndAttachSubDevice(config))
759 if (!openDeferredAttach(config)) {
781 if(!params.
check(
"ports"))
784 if (Network::exists(streamingPortName +
"/rpc:i") || Network::exists(streamingPortName))
789 createPort((streamingPortName ).c_str(), _rate );
791 if (!Network::exists(streamingPortName +
"/rpc:i")) {
799 Value &deviceChannels = params.
find(
"channels");
800 if (deviceChannels.
isNull())
806 int nports=ports->
size();
807 int sumOfChannels = 0;
808 std::vector<AnalogPortEntry> tmpPorts;
809 tmpPorts.resize(nports);
811 for(
size_t k=0; k<ports->
size(); k++)
815 if (parameters.
size()!=5)
817 yCError(
ANALOGWRAPPER) <<
"AnalogWrapper: check skin port parameters in part description, I was expecting "
818 << ports->
get(k).
asString().c_str() <<
" followed by four integers";
823 if (Network::exists(streamingPortName +
"/" + std::string(ports->
get(k).
asString()) +
"/rpc:i")
824 || Network::exists(streamingPortName +
"/" + std::string(ports->
get(k).
asString())))
837 if(wTop-wBase != top-base){
839 << ports->
get(k).
asString().c_str() <<
" port parameters in part description";
842 int portChannels = top-base+1;
844 tmpPorts[k].length = portChannels;
845 tmpPorts[k].offset = wBase;
847 tmpPorts[k].port_name = streamingPortName+
"/" + std::string(ports->
get(k).
asString());
849 sumOfChannels+=portChannels;
851 createPorts(tmpPorts, _rate);
853 if (sumOfChannels!=deviceChannels.
asInt32())
855 yCError(
ANALOGWRAPPER) <<
"AnalogWrapper: Total number of mapped taxels does not correspond to total taxels";
866 for(
auto& analogPort : analogPorts)
868 analogPort.port.interrupt();
869 analogPort.port.close();
875 int first, last,
ret;
877 if (analogSensor_p!=
nullptr)
879 ret=analogSensor_p->
read(lastDataRead);
883 if (lastDataRead.
size()>0)
889 for(
auto& analogPort : analogPorts)
892 first = analogPort.offset;
893 if (analogPort.length == -1) {
894 last = lastDataRead.
size()-1;
896 last = analogPort.offset + analogPort.length - 1;
900 if(last>=(
int)lastDataRead.
size()){
901 yCError(
ANALOGWRAPPER, )<<
"AnalogWrapper: error while sending analog sensor output on port "<< analogPort.port_name
902 <<
" Vector size expected to be at least "<<last<<
" whereas it is "<< lastDataRead.
size();
905 pv = lastDataRead.
subVector(first, last);
907 analogPort.port.setEnvelope(lastStateStamp);
908 analogPort.port.
write();
912 if (useROS !=
ROS_disabled && rosMsgType ==
"geometry_msgs/WrenchStamped")
914 std::vector<yarp::rosmsg::geometry_msgs::WrenchStamped> rosDataVec;
915 rosDataVec.resize(rosPublisherWrenchPortVec.size());
917 for(
size_t i = 0; i < rosDataVec.size(); i++)
919 rosDataVec.at(i).header.seq = rosMsgCounterVec.at(i)++;
921 rosDataVec.at(i).header.frame_id = frame_idVec.at(i);
923 rosDataVec.at(i).wrench.force.x = lastDataRead[(rosOffset + 6 + rosPadding) * i + 0];
924 rosDataVec.at(i).wrench.force.y = lastDataRead[(rosOffset + 6 + rosPadding) * i + 1];
925 rosDataVec.at(i).wrench.force.z = lastDataRead[(rosOffset + 6 + rosPadding) * i + 2];
927 rosDataVec.at(i).wrench.torque.x = lastDataRead[(rosOffset + 6 + rosPadding) * i + 3];
928 rosDataVec.at(i).wrench.torque.y = lastDataRead[(rosOffset + 6 + rosPadding) * i + 4];
929 rosDataVec.at(i).wrench.torque.z = lastDataRead[(rosOffset + 6 + rosPadding) * i + 5];
931 rosPublisherWrenchPortVec.at(i).write(rosDataVec.at(i));
934 else if (useROS !=
ROS_disabled && rosMsgType ==
"sensor_msgs/JointState")
937 size_t data_size = lastDataRead.
size();
938 rosData.
name.resize(data_size);
941 rosData.
effort.resize(data_size);
943 if (data_size != ros_joint_names.size())
945 yCDebug(
ANALOGWRAPPER) <<
"Invalid jointNames size:" << data_size <<
"!=" << ros_joint_names.size();
949 for (
size_t i = 0; i< data_size; i++)
954 rosData.
name[i] = ros_joint_names[i];
961 rosData.
header.
seq = rosMsgCounterVec.at(0)++;
963 rosPublisherJointPort.
write(rosData);
968 yCError(
ANALOGWRAPPER,
"AnalogWrapper: %s: vector size non valid: %lu", sensorId.c_str(),
static_cast<unsigned long> (lastDataRead.
size()));
975 case IAnalogSensor::AS_OVF:
978 case IAnalogSensor::AS_TIMEOUT:
981 case IAnalogSensor::AS_ERROR:
993 if (PeriodicThread::isRunning())
995 PeriodicThread::stop();
1003 subDeviceOwned->
close();
1004 delete subDeviceOwned;
1005 subDeviceOwned =
nullptr;
1008 if(rosNode!=
nullptr) {
const yarp::os::LogComponent & ANALOGWRAPPER()
define control board standard interfaces
constexpr yarp::conf::vocab32_t VOCAB_FAILED
constexpr yarp::conf::vocab32_t VOCAB_IANALOG
constexpr yarp::conf::vocab32_t VOCAB_CALIBRATE
constexpr yarp::conf::vocab32_t VOCAB_CALIBRATE_CHANNEL
static void handler(int sig)
constexpr double DEFAULT_THREAD_PERIOD
A yarp port that output data read from an analog sensor.
AnalogPortEntry & operator=(const AnalogPortEntry &alt)
yarp::os::BufferedPort< yarp::sig::Vector > port
AnalogPortEntry()
A yarp port that output data read from an analog sensor.
Handler of the rpc port related to an analog sensor.
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
AnalogServerHandler(const char *n)
Handler of the rpc port related to an analog sensor.
void setInterface(yarp::dev::IAnalogSensor *is)
bool _handleIAnalog(yarp::os::Bottle &cmd, yarp::os::Bottle &reply)
void threadRelease() override
Release method.
void attach(yarp::dev::IAnalogSensor *s)
bool threadInit() override
Initialization method.
~AnalogWrapper() override
void run() override
Loop function.
bool open(yarp::os::Searchable ¶ms) override
Open the DeviceDriver.
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).
bool view(T *&x)
Get an interface to the device driver.
A generic interface to sensors (gyro, a/d converters).
virtual int calibrateSensor()=0
Calibrates the whole sensor.
virtual int read(yarp::sig::Vector &out)=0
Read a vector from the sensor.
virtual int getChannels()=0
Get the number of channels of the sensor.
virtual int calibrateChannel(int ch)=0
Calibrates one single channel.
A container for a device driver.
bool close() override
Close the DeviceDriver.
bool isValid() const
Check if device is valid.
bool open(const std::string &txt)
Construct and configure a device by its common name.
A simple collection of objects that can be described and transmitted in a portable way.
void addVocab32(yarp::conf::vocab32_t x)
Places a vocabulary item in the bottle, at the end of the list.
size_type size() const
Gets the number of elements in the bottle.
bool read(ConnectionReader &reader) override
Set the bottle's value based on input from a network connection.
Value & get(size_type index) const
Reads a Value v from a certain part of the list.
Bottle & findGroup(const std::string &key) const override
Gets a list corresponding to a given keyword.
bool check(const std::string &key) const override
Check if there exists a property of the given name.
void clear()
Empties the bottle of any objects it contains.
bool write(ConnectionWriter &writer) const override
Output a representation of the bottle to a network connection.
void addInt32(std::int32_t x)
Places a 32-bit integer in the bottle, at the end of the list.
bool isNull() const override
Checks if the object is invalid.
std::string toString() const override
Gives a human-readable textual representation of the bottle.
Value & find(const std::string &key) const override
Gets a value corresponding to a given keyword.
An interface for reading from a network connection.
virtual ConnectionWriter * getWriter()=0
Gets a way to reply to the message, if possible.
An interface for writing to a network connection.
void interrupt()
interrupt delegates the call to the Node port interrupt.
An abstraction for a periodic thread.
bool setPeriod(double period)
Set the (new) period of the thread.
Interface implemented by all objects that can read themselves from the network, such as Bottle object...
A mini-server for network communication.
void setReader(PortReader &reader) override
Set an external reader for port data.
void close() override
Stop port activity.
bool open(const std::string &name) override
Start port operation, with a specific name, with automatically-chosen network parameters.
A class for storing options and configuration information.
void fromString(const std::string &txt, bool wipe=true)
Interprets a string as a list of properties.
void put(const std::string &key, const std::string &value)
Associate the given key with the given string.
void unput(const std::string &key)
Remove the association from the given key to a value, if present.
bool topic(const std::string &name)
Set topic to publish to.
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.
virtual Bottle & findGroup(const std::string &key) const =0
Gets a list corresponding to a given keyword.
void update()
Set the timestamp to the current time, and increment the sequence number (wrapping to 0 if the sequen...
A single value (typically within a Bottle).
virtual yarp::conf::float64_t asFloat64() const
Get 64-bit floating point value.
virtual bool isString() const
Checks if value is a string.
virtual yarp::conf::vocab32_t asVocab32() const
Get vocabulary identifier as an integer.
virtual std::int32_t asInt32() const
Get 32-bit integer value.
virtual bool isList() const
Checks if value is a list.
virtual Bottle * asList() const
Get list value.
virtual bool isInt32() const
Checks if value is a 32-bit integer.
bool isNull() const override
Checks if the object is invalid.
virtual std::string asString() const
Get string value.
std::vector< std::string > name
std::vector< yarp::conf::float64_t > position
std::vector< yarp::conf::float64_t > velocity
std::vector< yarp::conf::float64_t > effort
yarp::rosmsg::std_msgs::Header header
bool write(yarp::os::ConnectionWriter &connection) const override
Write vector to a connection.
void resize(size_t size) override
Resize the vector.
VectorOf< T > subVector(unsigned int first, unsigned int last) const
Creates and returns a new vector, being the portion of the original vector defined by the first and l...
#define yCInfo(component,...)
#define yCError(component,...)
#define yCTrace(component,...)
#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.
double now()
Return the current time in seconds, relative to an arbitrary starting point.
An interface to the operating system, including Port based communication.
bool read(ImageOf< PixelRgb > &dest, const std::string &src, image_fileformat format=FORMAT_ANY)
The main, catch-all namespace for YARP.
double convertDegreesToRadians(double degrees)
convert degrees to radiants for ROS messages