|
YARP
Yet Another Robot Platform
|
|
Go to the documentation of this file.
37 streaming_parser.
init(
this);
38 RPC_parser.
init(
this);
41 void ControlBoardWrapper::cleanup_yarpPorts()
48 inputStreamingPort.interrupt();
49 inputStreamingPort.close();
52 outputPositionStatePort.
close();
55 extendedOutputStatePort.
close();
75 if (rosNode !=
nullptr) {
83 if (subDeviceOwned !=
nullptr) {
84 subDeviceOwned->
close();
85 delete subDeviceOwned;
86 subDeviceOwned =
nullptr;
94 bool ControlBoardWrapper::checkPortName(
Searchable& params)
99 if (params.
check(
"rootName")) {
101 "************************************************************************************\n"
102 "* controlboardwrapper2 is using the deprecated parameter 'rootName' for port name, *\n"
103 "* It has to be removed and substituted with: *\n"
104 "* name: full port prefix name with leading '/', e.g. /robotName/part/ *\n"
105 "************************************************************************************";
110 if (!params.
check(
"name")) {
112 "************************************************************************************\n"
113 "* controlboardwrapper2 missing mandatory parameter 'name' for port name, usage is: *\n"
114 "* name: full port prefix name with leading '/', e.g. /robotName/part/ *\n"
115 "************************************************************************************";
122 "************************************************************************************\n"
123 "* controlboardwrapper2 'name' parameter for port name does not follow convention, *\n"
124 "* it MUST start with a leading '/' since it is used as the full prefix port name *\n"
125 "* name: full port prefix name with leading '/', e.g. /robotName/part/ *\n"
126 "* A temporary automatic fix will be done for you, but please fix your config file *\n"
127 "************************************************************************************";
136 bool ControlBoardWrapper::checkROSParams(
Searchable& config)
139 if (!config.
check(
"ROS")) {
154 if (!rosGroup.
check(
"useROS")) {
156 Allowed values are true, false, ROS_only";
160 std::string ros_use_type = rosGroup.
find(
"useROS").
asString();
161 if (ros_use_type ==
"false") {
167 if (ros_use_type ==
"true") {
170 }
else if (ros_use_type ==
"only") {
180 if (!rosGroup.
check(
"ROS_nodeName")) {
189 if (!rosGroup.
check(
"ROS_topicName")) {
194 rosTopicName = rosGroup.
find(
"ROS_topicName").
asString();
200 if (!rosGroup.
check(
"jointNames")) {
225 bool ControlBoardWrapper::initialize_ROS()
227 bool success =
false;
233 if (rosNode ==
nullptr) {
239 if (!rosPublisherPort.
topic(rosTopicName)) {
268 bool success =
false;
286 rootName = prop.
check(
"rootName",
Value(
"/"),
"starting '/' if needed.").asString();
287 partName = prop.
check(
"name",
Value(
"controlboard"),
"prefix for port names").asString();
289 if (rootName.find(
"//") != std::string::npos) {
290 rootName.replace(rootName.find(
"//"), 2,
"/");
294 if (!inputRPCPort.
open((rootName +
"/rpc:i"))) {
300 inputRPC_buffer.
attach(inputRPCPort);
301 RPC_parser.
attach(inputRPC_buffer);
303 if (!inputStreamingPort.open(rootName +
"/command:i")) {
310 inputStreamingPort.setStrict();
311 inputStreamingPort.useCallback(streaming_parser);
313 if (!outputPositionStatePort.
open(rootName +
"/state:o")) {
320 if (!extendedOutputStatePort.
open(rootName +
"/stateExt:o")) {
325 extendedOutputState_buffer.
attach(extendedOutputStatePort);
343 if (prop.
check(
"verbose",
"Deprecated flag. Use log components instead")) {
347 if (!checkPortName(config)) {
353 if (prop.
check(
"threadrate")) {
359 if (prop.
check(
"period")) {
371 period = default_period;
376 if (prop.
check(
"subdevice")) {
378 prop.setMonitor(config.getMonitor());
379 if (!openAndAttachSubDevice(prop)) {
385 if (!openDeferredAttach(prop)) {
395 if (!checkROSParams(config)) {
401 if (!initialize_ROS()) {
406 if (!initialize_YARP(prop)) {
420 PeriodicThread::setPeriod(period);
421 if (!PeriodicThread::start()) {
431 bool ControlBoardWrapper::openDeferredAttach(
Property& prop)
433 if (!prop.
check(
"networks",
"list of networks merged by this wrapper")) {
439 if (nets ==
nullptr) {
444 if (!prop.
check(
"joints",
"number of joints of the part")) {
450 size_t nsubdevices = nets->
size();
456 for (
size_t k = 0; k < nets->
size(); k++) {
465 if (parameters.
size() == 2) {
468 if (bot ==
nullptr) {
473 if (tmpBot.
size() != 4) {
475 <<
"--> I was expecting " << nets->
get(k).
asString() <<
" followed by a list of four integers in parenthesis"
476 <<
"Got: " << parameters.
toString();
484 wBase =
static_cast<size_t>(bot->
get(0).
asInt32());
485 wTop =
static_cast<size_t>(bot->
get(1).
asInt32());
486 base =
static_cast<size_t>(bot->
get(2).
asInt32());
487 top =
static_cast<size_t>(bot->
get(3).
asInt32());
488 }
else if (parameters.
size() == 5) {
490 wBase =
static_cast<size_t>(parameters.
get(1).
asInt32());
491 wTop =
static_cast<size_t>(parameters.
get(2).
asInt32());
492 base =
static_cast<size_t>(parameters.
get(3).
asInt32());
493 top =
static_cast<size_t>(parameters.
get(4).
asInt32());
496 <<
"--> I was expecting " << nets->
get(k).
asString() <<
" followed by a list of four integers in parenthesis"
497 <<
"Got: " << parameters.
toString();
507 size_t axes = top - base + 1;
516 <<
"First index " << wBase <<
"must be inside range from 0 to 'joints' (" <<
controlledJoints <<
")";
522 <<
"Second index " << wTop <<
"must be inside range from 0 to 'joints' (" <<
controlledJoints <<
")";
528 <<
"First index " << wBase <<
"must be lower than second index " << wTop;
532 for (
size_t j = wBase, jInDev = base; j <= wTop; j++, jInDev++) {
534 device.
lut[j].offset =
static_cast<int>(j - wBase);
550 bool ControlBoardWrapper::openAndAttachSubDevice(
Property& prop)
556 std::string subdevice = prop.
find(
"subdevice").
asString();
557 p.setMonitor(prop.getMonitor(), subdevice.c_str());
559 p.
put(
"device", subdevice);
563 subDeviceOwned->
open(p);
565 if (!subDeviceOwned->
isValid()) {
572 subDeviceOwned->
view(iencs);
574 if (iencs ==
nullptr) {
580 bool getAx = iencs->
getAxes(&tmp_axes);
602 std::string subDevName((
partName +
"_" + subdevice));
621 calculateMaxNumOfJointsInDevices();
625 void ControlBoardWrapper::calculateMaxNumOfJointsInDevices()
637 bool ControlBoardWrapper::updateAxisName()
655 vector<string> tmpVect;
661 std::string tmp2(tmp);
662 tmpVect.push_back(tmp2);
667 if (!jointNames.empty()) {
668 yCWarning(
CONTROLBOARDWRAPPER) <<
"Found 2 instance of jointNames parameter: one in the wrapper [ROS] group and another one in the subdevice, the latter one will be used.";
669 std::string fullNames;
671 fullNames.append(tmpVect[i]);
676 jointNames = tmpVect;
678 if (jointNames.empty()) {
684 "************************************************************************************************** \n" <<
685 "* Joint names for ROS topic were found in the [ROS] group in the wrapper config file for\n" <<
686 "* '" <<
partName <<
"' device.\n" <<
687 "* They should be in the MotionControl device(s) instead. Please update the config files.\n" <<
688 "**************************************************************************************************";
701 for (
int p = 0; p < polylist.
size(); p++) {
703 std::string tmpKey = polylist[p]->key;
704 if (tmpKey ==
"Calibrator" || tmpKey ==
"calibrator") {
707 polylist[p]->poly->view(calibrator);
709 IRemoteCalibrator::setCalibratorDevice(calibrator);
728 if (!subdevice.isAttached()) {
737 for (
int p = 0; p < polylist.
size(); p++) {
738 ss << polylist[p]->key.c_str() <<
" ";
748 calculateMaxNumOfJointsInDevices();
749 PeriodicThread::setPeriod(period);
750 return PeriodicThread::start();
766 for (
int k = 0; k < devices; k++) {
773 IRemoteCalibrator::releaseCalibratorDevice();
780 if (inputStreamingPort.getPendingReads() >= 20) {
781 yCWarning(
CONTROLBOARDWRAPPER) <<
"Number of streaming intput messages to be read is " << inputStreamingPort.getPendingReads() <<
" and can overflow";
804 jointData& yarp_struct = extendedOutputState_buffer.
get();
841 extendedOutputState_buffer.
write();
849 outputPositionStatePort.
write();
863 ros_struct.
name = jointNames;
868 rosPublisherPort.
write(ros_struct);
void close() override
Stop port activity.
bool getAxisName(int j, std::string &name) override
yarp::sig::VectorOf< int > controlMode
bool getMotorEncoderAccelerations(double *accs) override
Read the instantaneous acceleration of all motor encoders.
yarp::sig::VectorOf< double > torque
A simple collection of objects that can be described and transmitted in a portable way.
std::string toString() const override
Gives a human-readable textual representation of the bottle.
void put(const std::string &key, const std::string &value)
Associate the given key with the given string.
void resize(size_t size) override
Resize the vector.
A base class for nested structures that can be searched.
size_type size() const
Gets the number of elements in the bottle.
yarp::sig::VectorOf< double > pwmDutycycle
virtual Bottle & findGroup(const std::string &key) const =0
Gets a list corresponding to a given keyword.
@ VOCAB_JOINTTYPE_REVOLUTE
#define yCWarning(component,...)
void resize(int _deviceNum, int _maxJointsNumForDevice, WrappedDevice *_device)
Control board, encoder interface.
bool getInteractionModes(int n_joints, int *joints, yarp::dev::InteractionModeEnum *modes) override
Get the current interaction mode of the robot for a set of joints, values can be stiff or compliant.
virtual std::string toString() const =0
Return a standard text representation of the content of the object.
void fromString(const std::string &txt, bool wipe=true)
Interprets a string as a list of properties.
bool isValid() const
Check if device is valid.
bool motorAcceleration_isValid
double convertDegreesToRadians(double degrees)
convert degrees to radiants for ROS messages
yarp::sig::VectorOf< double > motorAcceleration
void interrupt() override
Interrupt any current reads or writes attached to the port.
bool removeCallbackLock() override
Remove a lock on callbacks added with setCallbackLock()
void fromString(const std::string &text)
Initializes bottle from a string.
bool setEnvelope(PortWriter &envelope) override
Set an envelope (e.g., a timestamp) to the next message which will be sent.
bool view(T *&x)
Get an interface to the device driver.
Value & find(const std::string &key) const override
Gets a value corresponding to a given keyword.
bool open(const std::string &name) override
Start port operation, with a specific name, with automatically-chosen network parameters.
std::vector< yarp::conf::float64_t > effort
void attach(Port &port)
Attach this buffer to a particular port.
bool motorVelocity_isValid
void init(yarp::dev::DeviceDriver *x)
Initialization.
bool close() override
Close the device driver by deallocating all resources and closing ports.
bool open(const std::string &txt)
Construct and configure a device by its common name.
void run() override
The thread main loop deals with writing on ports here.
void attach(yarp::os::TypedReader< yarp::os::Bottle > &source)
Attach this object to a source of messages.
bool isRunning() const
Returns true when the thread is started, false otherwise.
Value & find(const std::string &key) const override
Gets a value corresponding to a given keyword.
An interface for the device drivers.
yarp::sig::VectorOf< double > jointVelocity
bool setEnvelope(PortWriter &envelope) override
Set an envelope (e.g., a timestamp) to the next message which will be sent.
bool getMotorEncoderSpeeds(double *spds) override
Read the instantaneous speed of all motor encoders.
T & prepare()
Access the object which will be transmitted by the next call to yarp::os::BufferedPort::write.
bool check(const std::string &key) const override
Check if there exists a property of the given name.
yarp::sig::VectorOf< double > motorVelocity
Bottle & findGroup(const std::string &key) const override
Gets a list corresponding to a given keyword.
bool getJointType(int j, yarp::dev::JointTypeEnum &type) override
bool getMotorEncoders(double *encs) override
Read the position of all motor encoders.
bool topic(const std::string &name)
Set topic to publish to.
std::vector< yarp::conf::float64_t > velocity
Value & get(size_type index) const
Reads a Value v from a certain part of the list.
void write(bool forceStrict=false)
Write the current object being returned by Publisher::prepare.
std::string toString() const override
Return a standard text representation of the content of the object.
const yarp::os::LogComponent & CONTROLBOARDWRAPPER()
bool jointPosition_isValid
double getTime() const
Get the time stamp.
virtual std::string asString() const
Get string value.
bool pwmDutycycle_isValid
A container for a device driver.
SubDevice * getSubdevice(size_t i)
bool close() override
Close the DeviceDriver.
bool open(const std::string &name) override
Start port operation, with a specific name, with automatically-chosen network parameters.
SubDeviceVector subdevices
bool getDutyCycles(double *v) override
Gets the current dutycycle of the output of the amplifier (i.e.
virtual bool check(const std::string &key) const =0
Check if there exists a property of the given name.
bool getEncoderSpeeds(double *spds) override
Read the instantaneous speed of all axes.
virtual Value & find(const std::string &key) const =0
Gets a value corresponding to a given keyword.
~ControlBoardWrapper() override
yarp::rosmsg::std_msgs::Header header
bool check(const std::string &key) const override
Check if there exists a property of the given name.
iterator end() noexcept
Returns an iterator to the end of the VectorOf.
bool motorPosition_isValid
bool getEncoderAccelerations(double *accs) override
Read the instantaneous acceleration of all axes.
bool getTorques(double *t) override
Get the value of the torque for all joints (this is the feedback if you have torque sensors).
yarp::sig::VectorOf< double > motorPosition
yarp::sig::VectorOf< double > jointAcceleration
void setReader(PortReader &reader) override
Set an external reader for port data.
An abstraction for a periodic thread.
yarp::sig::VectorOf< double > jointPosition
yarp::sig::VectorOf< int > interactionMode
bool detachAll() override
Detach the object (you must have first called attach).
bool attachAll(const yarp::dev::PolyDriverList &l) override
Attach to a list of objects.
bool isNull() const override
Checks if the object is invalid.
void attach(Port &port)
Set the Port to which objects will be written.
bool jointAcceleration_isValid
virtual bool getAxes(int *ax)=0
Get the number of controlled axes.
Bottle tail() const
Get all but the first element of a bottle.
T * data()
Return a pointer to the first element of the vector.
An abstraction for a time stamp and/or sequence number.
#define yCError(component,...)
virtual std::int32_t asInt32() const
Get 32-bit integer value.
yarp::sig::VectorOf< double > current
void update()
Set the timestamp to the current time, and increment the sequence number (wrapping to 0 if the sequen...
void write(bool forceStrict=false)
Write the current object being returned by BufferedPort::prepare.
bool getCurrents(double *currs)
#define yCInfo(component,...)
An interface to the operating system, including Port based communication.
#define yCDebug(component,...)
std::vector< DevicesLutEntry > lut
bool getControlModes(int *modes) override
Get the current control mode (multiple joints).
The main, catch-all namespace for YARP.
void init(yarp::dev::DeviceDriver *x)
Initialization.
std::vector< std::string > name
T & get()
A synonym of PortWriterBuffer::prepare.
void write(bool forceStrict=false)
Try to write the last buffer returned by PortWriterBuffer::get.
void close() override
Stop port activity.
void interrupt() override
Interrupt any current reads or writes attached to the port.
virtual Bottle * asList() const
Get list value.
void stop()
Call this to stop the thread, this call blocks until the thread is terminated (and releaseThread() ca...
Bottle & findGroup(const std::string &key) const override
Gets a list corresponding to a given keyword.
virtual bool initialize()
Initialize the internal data.
std::string toString() const override
Return a standard text representation of the content of the object.
A single value (typically within a Bottle).
std::vector< yarp::conf::float64_t > position
size_t maxNumOfJointsInDevices
iterator begin() noexcept
Returns an iterator to the beginning of the VectorOf.
IRemoteCalibrator interface is meant to remotize the access of the calibration device in order to all...
void unput(const std::string &key)
Remove the association from the given key to a value, if present.
bool open(yarp::os::Searchable &prop) override
Open the device driver.
bool getEncodersTimed(double *encs, double *t) override
Read the instantaneous acceleration of all axes.
bool jointVelocity_isValid
bool interactionMode_isValid
A class for storing options and configuration information.
bool configure(size_t wbase, size_t wtop, size_t base, size_t top, size_t axes, const std::string &id, ControlBoardWrapper *_parent)
virtual bool isInt32() const
Checks if value is a 32-bit integer.