Closed PeterBowman closed 6 years ago
ros::NodeHandle
implements a similar solution for accessing the parameter server (ref1, ref2). ROS devs didn't hesitate to create overloads: ros::NodeHandle::getParam
x 16, ros::NodeHandle::setParam
x 16, plus their cached counterparts, and more, including generic methods (which I think we can't use in an abstract base class).
A remark on that: ROS does not place constraints on the parameter identifier (the key part, as opposed to the value). It's meant to be a plain std::string
which may point at any type of data, hence such a high number of overloads. Should we make them accept vocabs instead, a decision should be taken whether to define a narrow, basic set of properties in ICartesianControl.h
(e.g. VOCAB_CC_GAIN
), or delegate this responsibility to the implementors (e.g. BasicCartesianControl
and AmorCartesianControl
might accept different sets of vocabs). The latter imposes a serious restriction: client code must know beforehand how is the vocab encoded and construct it with yarp::os::Vocab::encode
prior to handling the vocab
parameter. This is obviously true for stringified parameter keys as well, but what is the point of enforcing a four-character limit for these descriptors, then?
Idea: publish some or all of these configuration parameters along with controller state and FK solution in stat()
(#102, #129). Discuss it here or at #118.
Maybe just double
and string
for now?
I'm going to forget about string
s for now... I can't see any valid use case for the time being.
Done at b0ccbf2. Currently enabled parameters:
No longer blocking #46.
Small follow-up at 944ec2a. Relevant changes:
cmcRateMs
(only BasicCartesianControl
)ICartesianControl::reference_frame
https://github.com/roboticslab-uc3m/kinematics-dynamics/blob/944ec2a6a65b20d875b4fd5f7a6bbeba27b30882/libraries/YarpPlugins/ICartesianControl.h#L100-L105movl
(we can issue linear offsets) and movv
movl
and pose
will crash unless controllerGain
is set to zeroClassy! Smooth! Nice!!
- important:
movl
andpose
will crash unlesscontrollerGain
is set to zero
Should that be happening? In simulation, zero gain should work, but a non-zero gain should be needed with real motors.
Classy! Smooth! Nice!!
Just a shameless copypasta from YARP đŸ˜„
Should that be happening? In simulation, zero gain should work, but a non-zero gain should be needed with real motors.
In fact, this is closely related to #136 because of a fwdKinError
call that does not support (yet) the TCP frame. See:
As a workaround, I suggest setting gain
to zero so that the buggy command does not influence subsequent operations.
Okay, understood. Thanks!
Another follow-up: commit 5ad5eea added two new methods for setting and retrieving multiple parameters at once. Also, set/get vocabs have been standardized. Example invocations via yarp rpc
:
get cpjv
: retrieve maximum joint velocityset cpjv 15
: set maximum joint velocity to 15
get prms
: retrieve all configuration parametersset prms (cpjv 15) (cpcr 60)
: set maximum joint velocity to 15
and CMC rate to 60
msVocabs may be passed either as plain strings or in brackets: cpjv
or [cpjv]
.
Yet another follow-up (YAFU, which vaguely resembles YAFUD): 1f62c00. Now, we can configure the check period within the implementors of ICartesianControl::wait
(#106):
https://github.com/roboticslab-uc3m/kinematics-dynamics/issues/121#issuecomment-359628756
The cpjv
(maximum joint velocity) parameter shall be removed after https://github.com/roboticslab-uc3m/yarp-devices/issues/188, and convenient calls to getVelLimits
performed on controller init (similarly to getLimits
).
Edit: see https://github.com/roboticslab-uc3m/kinematics-dynamics/issues/159.
As discussed with @jgvictores, we'd like to stop and avoid an increasing expansion of the list of commands at
ICartesianControl
(totalling 17 at the time of filing this issue). See background at #105.Influenced by
yarp::dev::ICartesianControl::tweakSet
andyarp::dev::ICartesianControl::tweakGet
, consider adding a pair of setter/getter RPC methods that would allow users to change a set of controller parameters on runtime, such as:movl
and the like (#46)switch between RPC/streaming modes?(mind return values!)Iin parallel to this, new configuration options should be implemented in the corresponding YARP devices (e.g.
yarpdev --device BasicCartesianControl --gain 0.15 ...
).Example signature:
Multiple overloads may seem like overkill and go against the initial movation of this issue, but C++ lacks a standard container similar to
yarp::os::Value
(at least not until C++17, see std::any).