Problems with KDL solutions
Submitted by focke_85 on Mon, 2011-11-21 16:13 |
Good afternoon to all
I've been having some problems with the inverse kinematics velocity solvers. I've been using the ChainIkSolverVel_pinv to get the joint velocity needed to move the end-effector of my manipulator with a given (Cartesian) velocity and orientation. In the most simple case, I'm just trying to move up and down the end-effector without changing it's orientation, so I'm only changing the Cartesian velocity in z-axis. The problem is than, after retrieving the joint velocity, I'm testing the solution vel_array with the ChainFkSolverVel_recursive, getting sometimes different results. Also, when I introduce a positive Cartesian velocity (C_Vel1), the iksolver returns some joint velocities array (J_Vel1), but when I introduce the same cartesian velocity but negative (C_Vel2 = -C_Vel1), the result of the iksolver is not equal in magnitude to the first one (J_Vel2 / -J_Vel1 < 1), so it is slower. Is that possible? I would really appreciate some help here, to know if I'm using something wrong.
The important part of the code I'm using is the following:
//--------------------------------------------------------------------PCMC_MoveArm_Vel2 bool PCMC_MoveArm_Vel2(float fVelY, float fVelZ){ Twist cartetianVel = Twist::Zero(); JntArray jointVel; cartetianVel(1) = fVelY; cartetianVel(2) = fVelZ; cout << "cartetianVel = " << endl; for (unsigned int i = 0; i < 6 ; i++) cout << "\t" << cartetianVel(i) << endl; if (!getInvKinematicsSolution_Vel(cartetianVel, jointVel)){ log(Error) << "Error getting the inverse kinematics solution."<<endlog(); return false; } cout << "jointVel = " << endl; for (unsigned int i = 0; i < jointVel.rows() ; i++){ for (unsigned int j = 0; j < jointVel.columns() ; j++){ cout << "\t" << jointVel(i,j); } cout << endl; } JntArrayVel jointPosVel (robotChain.getNrOfJoints()); FrameVel cartetianPosVel; //save modules'positions in the joint array for (int iModule = 0; iModule < NUM_MODULES ; iModule++){ float posTemp = getModulePosition(iModule); if (posTemp == -100){ log(Error) << "Error retrieving the actual position of module " << iModule <<endlog(); return false; } jointPosVel.q(iModule) = posTemp; } jointPosVel.qdot = jointVel; ChainFkSolverVel_recursive fkSolverVel (robotChain); fkSolverVel.JntToCart(jointPosVel, cartetianPosVel); cout << "\nrotationalVel = " << endl; for (unsigned int i = 0; i < 3 ; i++){ for (unsigned int j = 0; j < 3 ; j++){ cout << ",\t" << cartetianPosVel.M.R(i,j); } cout << "\t,\t" << cartetianPosVel.M.w(i) << endl; } cout << "\nvectorVel (position & velocity)) = " << endl; for (unsigned int i = 0; i < 3 ; i++){ cout << ",\t" << cartetianPosVel.p.p(i) << ",\t,\t" << cartetianPosVel.p.v(i) <<endl; } return true; }//moveArm_Vel2(float fDeltaX, float fDeltaY) //****************************************************************************getInvKinematicsSolution_Vel bool getInvKinematicsSolution_Vel (Twist cartetianVel_in, JntArray& jointVel_out){ //Creation of jntarrays: JntArray q_init(robotChain.getNrOfJoints()); JntArray jointVel(robotChain.getNrOfJoints()); int iReturnedValue = -1; Twist tTemp = Twist::Zero(); //save modules'positions in the joint array for (int iModule = 0; iModule < NUM_MODULES ; iModule++){ float posTemp = getModulePosition(iModule); if (posTemp == -100){ log(Error) << "Error retrieving the actual position of module " << iModule <<endlog(); return false; } q_init(iModule) = posTemp; } //Creation of the solvers: ChainIkSolverVel_pinv ikSolverVel(robotChain, 0.00001, 300);//Inverse velocity solver iReturnedValue = ikSolverVel.CartToJnt(q_init, cartetianVel_in, jointVel); jointVel_out = jointVel; return (iReturnedValue == 0); }//getInvKinematicsSolution_Vel
And some of the results I get are the following:
manipulatorController [S]> PCMC_MoveArm_Vel2 (0,0.05) cartetianVel = 0 0 0.05 0 0 0 jointVel = -1.48139e-13 -0.00194407 -4.65061e-13 0.00422237 -3.08953e-13 0.00948641 -2.53251e-08 rotationalVel = , 5.83701e-05, -1.11158e-05, -1 , -1.30774e-07 , 6.33889e-10, 1, -1.11158e-05 , 0.0117647 , 1, 1.49418e-11, 5.83701e-05 , 6.97855e-13 vectorVel (position & velocity)) = , -0.250001, , -9.51403e-08 , -2.77895e-06, , 1.73386e-12 , -0.858985, , 0.00294118 = true manipulatorController [S]> PCMC_MoveArm_Vel2 (0,-0.05) cartetianVel = 0 0 -0.05 0 0 0 jointVel = 1.68511e-06 3.94674 1.25643e-08 -8.57031 1.68308e-06 4.62357 3.87292e-05 rotationalVel = , 0.107912, -8.33506e-06, -0.99416 , -8.81769e-11 , 7.27825e-07, 1, -8.30502e-06 , 8.0127e-16 , 0.99416, 1.72635e-07, 0.107912 , -7.48163e-10 vectorVel (position & velocity)) = , -0.248454, , 3.71245e-07 , -2.07626e-06, , 1.97739e-10 , -0.831909, , -0.0500317 = true manipulatorController [S]> PCMC_MoveArm_Vel2 (0,-0.005) cartetianVel = 0 0 -0.005 0 0 0 jointVel = -4.61313e-09 0.0172615 -1.17433e-10 -0.0380367 -4.19319e-09 0.0207752 2.79315e-08 rotationalVel = , 0.173571, -1.23344e-06, -0.984821 , 6.90957e-19 , -4.15934e-07, 1, -1.32576e-06 , -6.8835e-19 , 0.984821, 6.39735e-07, 0.173571 , 5.99803e-19 vectorVel (position & velocity)) = , -0.240618, , -8.23963e-19 , -3.3144e-07, , -2.68847e-18 , -0.755318, , -0.005 = true manipulatorController [S]> PCMC_MoveArm_Vel2 (0,0.005) cartetianVel = 0 0 0.005 0 0 0 jointVel = -2.19491e-07 -0.239116 1.55272e-09 0.519272 -2.24708e-07 -0.280156 -3.15286e-06 rotationalVel = , 0.174556, -1.11091e-05, -0.984647 , 1.7581e-11 , 1.5605e-06, 1, -1.10057e-05 , 3.08316e-16 , 0.984647, 3.84566e-07, 0.174556 , 9.91816e-11 vectorVel (position & velocity)) = , -0.246288, , 2.04956e-16 , -2.75143e-06, , -2.5182e-11 , -0.815054, , 0.005 = true
As you can see, here are 4 samples. In the first shows the first problem I mentioned above, while the 3th and 4th show the second problem.
Thanks in advance, Santiago
Re:
Hi Ruben, thanks for the reply
> Could it be that your structure is in some singular pose?
Its seems it was. I changed the initial position to a more "central" one and it seems that the 1st problem disappeared.
> I also noticed that you have a redundant robot. In this case it is perfectly > possible to get different results when you just reverse the sign of the > cartesian velocity.
Yes, I'm working with a redundant robot. But in the case of the examples, just 3 of the 7 joints are moving. In both cases (positive and negative) the velocity of the joints 0,2,4,6 is 0. And with the other 3, the joint velocity magnitude of the 'negative' solution is smaller that the one in the 'positive' solution (for the 3 joints). Even when moving the manipulator it can be seen that the 'negative' solution is somehow slower than the 'positive' one.
> In the end it is only the first case that shows irregular results, in the other > 3 examples the inverse and forward kinematics seem to be consistent.
> Could the problem be related to the reading of your positions (you read them > independently in the inverse and the forward case)
Problems with KDL solutions
On Monday 21 November 2011 17:13:05 focke [dot] 85 [..] ... wrote:
> Good afternoon to all
>
> I've been having some problems with the inverse kinematics velocity solvers.
> I've been using the ChainIkSolverVel_pinv to get the joint velocity needed
> to move the end-effector of my manipulator with a given (Cartesian)
> velocity and orientation. In the most simple case, I'm just trying to move
> up and down the end-effector without changing it's orientation, so I'm only
> changing the Cartesian velocity in z-axis. The problem is than, after
> retrieving the joint velocity, I'm testing the solution vel_array with the
> ChainFkSolverVel_recursive, getting sometimes different results. Also, when
> I introduce a positive Cartesian velocity (C_Vel1), the iksolver returns
> some joint velocities array (J_Vel1), but when I introduce the same
> cartesian velocity but negative (C_Vel2 = -C_Vel1), the result of the
> iksolver is not equal in magnitude to the first one (J_Vel2 / -J_Vel1 < 1),
> so it is slower. Is that possible? I would really appreciate some help
> here, to know if I'm using something wrong.
Could it be that your structure is in some singular pose?
I also noticed that you have a redundant robot. In this case it is perfectly
possible to get different results when you just reverse the sign of the
cartesian velocity.
In the end it is only the first case that shows irregular results, in the other
3 examples the inverse and forward kinematics seem to be consistent.
Could the problem be related to the reading of your positions (you read them
independently in the inverse and the forward case)
(no subject)
On Tuesday 22 November 2011 14:48:28 focke [dot] 85 [..] ... wrote:
>
>
> wrote:
> >> Good afternoon to all
> >>
> >> I've been having some problems with the inverse kinematics velocity
>
> solvers.
>
> >> I've been using the ChainIkSolverVel_pinv to get the joint velocity
> >> needed to move the end-effector of my manipulator with a given
> >> (Cartesian) velocity and orientation. In the most simple case, I'm
> >> just trying to move up and down the end-effector without changing
> >> it's orientation, so I'm
> only
>
> >> changing the Cartesian velocity in z-axis. The problem is than,
> >> after
> >> retrieving the joint velocity, I'm testing the solution vel_array
> >> with the ChainFkSolverVel_recursive, getting sometimes different
> >> results. Also,
> when
>
> >> I introduce a positive Cartesian velocity (C_Vel1), the iksolver
> >> returns some joint velocities array (J_Vel1), but when I introduce
> >> the same cartesian velocity but negative (C_Vel2 = -C_Vel1), the
> >> result of the iksolver is not equal in magnitude to the first one
> >> (J_Vel2 / -J_Vel1 <
> 1),
>
> >> so it is slower. Is that possible? I would really appreciate some
> >> help
> >> here, to know if I'm using something wrong.
>
> Hi Ruben, thanks for the reply
>
> > Could it be that your structure is in some singular pose?
>
> Its seems it was. I changed the initial position to a more "central" one and
> it seems that the 1st problem disappeared.
>
> > I also noticed that you have a redundant robot. In this case it is
>
> perfectly
>
> > possible to get different results when you just reverse the sign of
> > the
> > cartesian velocity.
>
> Yes, I'm working with a redundant robot. But in the case of the examples,
> just 3 of the 7 joints are moving. In both cases (positive and negative) the
> velocity of the joints 0,2,4,6 is 0. And with the other 3, the joint
> velocity magnitude of the 'negative' solution is smaller that the one in
> the 'positive' solution (for the 3 joints). Even when moving the
> manipulator it can be seen that the 'negative' solution is somehow slower
> than the 'positive' one.
The forward velocity kinematics clearly shows that the magnitude of the
resulting cartesian velocity is equal. Since you have a redundant robot and
you did not specify a redundancy resolution criteria, (which is not possible
with the pinv version of the inverse velocity solver) I do not see the
problem. You might want to take a look at the wdls version which provides more
features.
> > In the end it is only the first case that shows irregular results, in
> > the
> other
>
> > 3 examples the inverse and forward kinematics seem to be consistent.
> >
> > Could the problem be related to the reading of your positions (you
> > read
>
> them
>
> > independently in the inverse and the forward case)
(no subject)
2011/12/14 miguel [dot] prada [dot] sarasola [..] ... <miguel [dot] prada [dot] sarasola [..] ...>:
[...]
>
> I will probably use the code as it is and hope that chance saves me from
> having such a difference to compute. If I happen to encounter this while
> running my experiments and I generate a patch for the implementation of
> GetRot and/or GetRotAngle, where should I post it?
http://bugs.orocos.org/enter_bug.cgi
Steven
>
> Best regards,
>
> Miguel.
> --
> Orocos-Users mailing list
> Orocos-Users [..] ...
> http://lists.mech.kuleuven.be/mailman/listinfo/orocos-users
(no subject)
Hi Santiago,
On Mon, Feb 6, 2012 at 8:46 PM, <focke [dot] 85 [..] ...> wrote:
> Hi Peter. Thanks for the reply
>
> > Hi Santiago,
>
> > On Fri, Feb 3, 2012 at 5:50 PM, wrote:
>
> >> Actually I've measured the period time the master component is spending,
> and I realized that the period increases from ~0.001 to ~0.1 seconds every
> time I call a driver's method from my controller Orocos component that adds
> data to a local vector.
>
>
> >> bool SoemCanEthercat::addOutputCANmessage(can_message
> outputCanMessage) {
> tx_message tx_msg_temp;
> tx_msg_temp.transaction_nr = m_tx_transaction_nr;
> tx_msg_temp.can_msg = outputCanMessage;
> m_tx_transaction_nr++;
> m_input_can_messages.insert( m_input_can_messages.begin() ,
> tx_msg_temp );
> return true;
> }//SoemCanEthercat::addOutputCANmessage
>
>
> >> The data in that vector is later written to the 'outputs' of the slave
> during the updateHook of the master component, where the update method of the
> slave driver is called.
>
>
> > Are you sure updateHook is never called during addOutputCANmessage ?
>
> The addOutputCANmessage methods is exactly as posted above. The master's
> updateHook is not called from it.
>
> I made a small test, where I stopped calling the driver's method
> addOutputCANmessage. So, in this moment I just have the periodical soem
> master and a non-periodical controller component (Orocos task context). In
> the controller I'm printing, during the configureHook, a message in the
> console every 0.02 sec for some time and then return true. In the master
> updateHook i'm printing a message as well, with a master period of 0.01 sec.
> When I run master it prints the master messages periodically. But when I
> configure the controller, the master stops printing its messages until the
> controller finishes the configureHook. Apparently both components
> (taskContexts) are being executed in the same thread, or something is
> happening that makes that the master component thread is not processed while
> the controller component is being configured. The same code worked without
> Xenomai. What can be happening with the Orocos components and how could I
> solve this problem?
Well, I'm guessing Xenomai is more 'correct' than gnulinux. Since the
operation is OwnThread,
it is executed in the thread of the component owning that operation.
If that component has a
higher priority than the SOEM master, the SOEM master will be suspended, and the
addOutputCANmessage function executed by the controller.
You can check your priorities by doing:
cat /proc/xenomai/sched
from a console. But also check my reply below, which is a more possible cause...
>
>
> >> Obviously, this period time is much more than the expected one. I checked
> the time the driver spends in the 'addOutputCANmessage' and 'update' methods
> and is just about a few microsecond, so the delay is not there. This wasn't
> happening before changing to Xenomai. What can be causing this excessive
> delay in my master?
>
> > What we did to get soem working on Xenomai is to use rtnet instead of plain
> Linux sockets, just in case the delay is caused by this.... It's no use
> switching to Xenomai for SOEM if you don't use rtnet.
>
> But is it possible to use SOEM with Xenomai and plain Linux sockets? or is
> RTNet required?
It's not required, it just makes very little sense, and leads to
priority inversions.
It means that any component *not* using plain Linux sockets will have a de facto
higher priority than the thread using the Linux sockets. This is called domain
switches in Xenomai, and leads to exactly the behavior you are describing.
So from this perspective, rtnet is required.
>
> > Ruben, is this method/option already in the SOEM repos ?
>
>
> >> The driver was coded following the Beckhoff drivers in the SOEM/Orocos
> master stack, except that I'm using an operation to receive the process data
> that will be sent to the slaves, and an Orocos port to publish the process
> data the the driver receives from the slave.
>
> > This should be ok, but be sure that your operation is OwnThread in case you
> don't use any mutexes.
>
> The operation is OwnThread
>
> >Peter
>
>
> Santiago
Peter
(no subject)
Hi Peter
Thanks for the reply. I read the principle of Xenomai and Adeos and I
understand what you are saying. I installed RTNET from the git repository
by following this steps:
cd /usr/src/rtnet
sudo make menuconfig #setting xenomai
sudo make
sudo make install
sudo mknod /dev/renet c 10 240
Nevertheless the problem continues. I'm sure I'm missing some steps in the
installation and setting up of RTNET, but I haven"t find a clear
step-by-step explanation. I know that at some point I have to install some
RTNET modules (rtnet, rt_e1000, etc) but I don't understand exactly how. My
intention is to leave eth0 for non-RT networks and eth1 for the EtherCAT
network (I'm using the e1000e network driver).
I've tried doing ' ifconfing eth1 down ' and settting
rtnet/etc/rtnet.config with
RT_DRIVER="rt_e1000"
RT_DRIVER_OPTIONS="cards=0,1"
TDMA_MODE="master"
(I dont know exactly what should I put in IPADDR, NETMASK and TDMA_SLAVES)
Then I run ' ./rtnet/sbin/rtnet start ' (that I've seen that configures and
install the rtnet modules automatically) but I get the following errors:
rteth0: ERROR while getting interface flags: No such device
rteth0-mac: ERROR while getting interface flags: No such device
ioctl: No such device
ioctl: No such device
ioctl: No such device
ioctl: No such device
ioctl (add): No such device
vnic0: ERROR while getting interface flags: No such device
SIOCSIFADDR: No such device
vnic0: ERROR while getting interface flags: No such device
Waiting for all slaves...ioctl: No such device
ioctl: No such device
Running ifconfig I see that I dont have any rteth0 or rteth1, just a rtlo.
And when I configure the mater component after running 'rtnet start' , it
throws
Deployer [S]> EtherCat_Master.configure
getting socket index failed:-1, Operation not permitted
resetting socket flags failed:-1, Operation not permitted
setting socket flags failed:-1, Operation not permitted
23.882 [ Info ][EtherCat_Master] ec_init on eth1 succeeded.
and stays there indefinitely.
Also, I would like to know if I should keep initializing the SOEM master
with eth1? or should I do it with rteth1 or something like that?
BR,
2012/2/6 Peter Soetens <peter [..] ...>
> Hi Santiago,
>
> On Mon, Feb 6, 2012 at 8:46 PM, <focke [dot] 85 [..] ...> wrote:
> > Hi Peter. Thanks for the reply
> >
> > > Hi Santiago,
> >
> > > On Fri, Feb 3, 2012 at 5:50 PM, wrote:
> >
> > >> Actually I've measured the period time the master component is
> spending,
> > and I realized that the period increases from ~0.001 to ~0.1 seconds
> every
> > time I call a driver's method from my controller Orocos component that
> adds
> > data to a local vector.
> >
> >
> > >> bool SoemCanEthercat::addOutputCANmessage(can_message
> > outputCanMessage) {
> > tx_message tx_msg_temp;
> > tx_msg_temp.transaction_nr = m_tx_transaction_nr;
> > tx_msg_temp.can_msg = outputCanMessage;
> > m_tx_transaction_nr++;
> > m_input_can_messages.insert( m_input_can_messages.begin()
> ,
> > tx_msg_temp );
> > return true;
> > }//SoemCanEthercat::addOutputCANmessage
> >
> >
> > >> The data in that vector is later written to the 'outputs' of the
> slave
> > during the updateHook of the master component, where the update method
> of the
> > slave driver is called.
> >
> >
> > > Are you sure updateHook is never called during addOutputCANmessage ?
> >
> > The addOutputCANmessage methods is exactly as posted above. The master's
> > updateHook is not called from it.
> >
> > I made a small test, where I stopped calling the driver's method
> > addOutputCANmessage. So, in this moment I just have the periodical soem
> > master and a non-periodical controller component (Orocos task context).
> In
> > the controller I'm printing, during the configureHook, a message in the
> > console every 0.02 sec for some time and then return true. In the master
> > updateHook i'm printing a message as well, with a master period of 0.01
> sec.
> > When I run master it prints the master messages periodically. But when I
> > configure the controller, the master stops printing its messages until
> the
> > controller finishes the configureHook. Apparently both components
> > (taskContexts) are being executed in the same thread, or something is
> > happening that makes that the master component thread is not processed
> while
> > the controller component is being configured. The same code worked
> without
> > Xenomai. What can be happening with the Orocos components and how could I
> > solve this problem?
>
> Well, I'm guessing Xenomai is more 'correct' than gnulinux. Since the
> operation is OwnThread,
> it is executed in the thread of the component owning that operation.
> If that component has a
> higher priority than the SOEM master, the SOEM master will be suspended,
> and the
> addOutputCANmessage function executed by the controller.
>
> You can check your priorities by doing:
>
> cat /proc/xenomai/sched
>
> from a console. But also check my reply below, which is a more possible
> cause...
>
> >
> >
> > >> Obviously, this period time is much more than the expected one. I
> checked
> > the time the driver spends in the 'addOutputCANmessage' and 'update'
> methods
> > and is just about a few microsecond, so the delay is not there. This
> wasn't
> > happening before changing to Xenomai. What can be causing this excessive
> > delay in my master?
> >
> > > What we did to get soem working on Xenomai is to use rtnet instead of
> plain
> > Linux sockets, just in case the delay is caused by this.... It's no use
> > switching to Xenomai for SOEM if you don't use rtnet.
> >
> > But is it possible to use SOEM with Xenomai and plain Linux sockets? or
> is
> > RTNet required?
>
> It's not required, it just makes very little sense, and leads to
> priority inversions.
> It means that any component *not* using plain Linux sockets will have a de
> facto
> higher priority than the thread using the Linux sockets. This is called
> domain
> switches in Xenomai, and leads to exactly the behavior you are describing.
>
> So from this perspective, rtnet is required.
>
> >
> > > Ruben, is this method/option already in the SOEM repos ?
> >
> >
> > >> The driver was coded following the Beckhoff drivers in the
> SOEM/Orocos
> > master stack, except that I'm using an operation to receive the process
> data
> > that will be sent to the slaves, and an Orocos port to publish the
> process
> > data the the driver receives from the slave.
> >
> > > This should be ok, but be sure that your operation is OwnThread in
> case you
> > don't use any mutexes.
> >
> > The operation is OwnThread
> >
> > >Peter
> >
> >
> > Santiago
>
> Peter
>
(no subject)
On Mon, Feb 6, 2012 at 6:13 PM, <paul [dot] chavent [..] ...> wrote:
>
> make more sense (i.e. make it more robust to these kind of errors).
> Moreover, it would be backward compatible with the old behavior that was to
> signal by default...
>
> And what should we do when CORBA::is_nil(remote_side.in()) is true
> (exception, return false ...) ?
On which file/line ?
>
> I still have a question about the RemoteChannelElement. Is there any method
> that is always called at connection time, where we could call
> propagateNeedsSignal for caching its return value ?
After a connection is created, the input port will call ready() on the
connection,
which is propagated backwards towards the output port. Otherwise, the output
port (and every channel element of the connection) has no way
to know when the connection is 'functional'.
>
>
> There is a last point to discuss : in addition to caching the return value of
> propagateNeedsSignal upon connection, I would like to update this value when
> signalInterface is called. Is it a good idea ? Is there other functions that
> can change this value ?
signalInterface is currently only called by the data flow interface to
tell the port
it has been added as an event port. After that, it is never called
anymore by RTT.
Since this is a public function a user could try to call this function
as well, in which
case our behavior would no longer match. I'd prefer to make DataFlowInterface
a friend of InputPortInterface and make signalInterface
protected/private, instead of
trying to work around incorrect use of the API.
Peter
(no subject) (was Port conenction over corba)
Le 02/06/2012 10:28 PM, Peter Soetens a écrit :
> On which file/line ?
In the transport/corba/RemoteChannelElement.hpp file. If we haven't any remote side, should we silently fail or throw an exception ?
Le 02/06/2012 10:28 PM, Peter Soetens a écrit :
> signalInterface is currently only called by the data flow interface to
> tell the port
> it has been added as an event port. After that, it is never called
> anymore by RTT.
> Since this is a public function a user could try to call this function
> as well, in which
> case our behavior would no longer match.
:) I do such things, because i have a "generic" function that add a ports. After this function was called, the user can tune the ports he desires to be "EventPorts".
Le 02/07/2012 10:30 AM, Sylvain Joyeux a écrit :
> Just for my information, what is the signalInterface ?
I use it to transform an input port in an event input port.
I would like to purpose an alternative to the first patch with an other approach.
I changed the
bool propagateNeedsSignaling()
to
void propagateNeedsSignaling(bool)
So instead of asking the needsSignaling state, the input port says whenever he changes its signaling state.
The RemoteChannelElement catch this call and cache the value.
Paul.
(no subject) (was Port conenction over corba)
On Tue, Feb 7, 2012 at 3:18 PM, Paul Chavent <paul [dot] chavent [..] ...> wrote:
> Le 02/06/2012 10:28 PM, Peter Soetens a écrit :
>>
>> On which file/line ?
>
>
> In the transport/corba/RemoteChannelElement.hpp file. If we haven't any
> remote side, should we silently fail or throw an exception ?
>
>
> Le 02/06/2012 10:28 PM, Peter Soetens a écrit :
>>
>> signalInterface is currently only called by the data flow interface to
>> tell the port
>> it has been added as an event port. After that, it is never called
>> anymore by RTT.
>> Since this is a public function a user could try to call this function
>> as well, in which
>> case our behavior would no longer match.
>
>
> :) I do such things, because i have a "generic" function that add a ports.
> After this function was called, the user can tune the ports he desires to be
> "EventPorts".
>
>
> Le 02/07/2012 10:30 AM, Sylvain Joyeux a écrit :
>>
>> Just for my information, what is the signalInterface ?
>
>
> I use it to transform an input port in an event input port.
>
>
>
> I would like to purpose an alternative to the first patch with an other
> approach.
>
> I changed the
> bool propagateNeedsSignaling()
> to
> void propagateNeedsSignaling(bool)
>
> So instead of asking the needsSignaling state, the input port says whenever
> he changes its signaling state.
>
> The RemoteChannelElement catch this call and cache the value.
Didn't look in detail yet, but the concept is fine for me.
Peter
(no subject)
On 02/06/2012 10:28 PM, Peter Soetens wrote:
>> I still have a question about the RemoteChannelElement. Is there any method
>> that is always called at connection time, where we could call
>> propagateNeedsSignal for caching its return value ?
Since propagateNeedsSignal is recursive, you will need to add the call
to propagateNeedsSignal separately inside the connection logic
(otherwise, every ready() calls will call propagateNeedsSignal
recursively ... not very nice). Or "fuse" it in the current ready() call.
>> There is a last point to discuss : in addition to caching the return value of
>> propagateNeedsSignal upon connection, I would like to update this value when
>> signalInterface is called. Is it a good idea ? Is there other functions that
>> can change this value ?
>
> signalInterface is currently only called by the data flow interface to
> tell the port
> it has been added as an event port. After that, it is never called
> anymore by RTT.
> Since this is a public function a user could try to call this function
> as well, in which
> case our behavior would no longer match. I'd prefer to make DataFlowInterface
> a friend of InputPortInterface and make signalInterface
> protected/private, instead of
> trying to work around incorrect use of the API.
Just for my information, what is the signalInterface ? Originally, the
port was generating an event... Provided that it is still actual (I sure
hope it is since it is something I was planning to build upon), I
personally think that the signalling behaviour should work as soon as
this event is created. Which can be done by the user. However, I believe
that we can mandate that the change from non-signalling to signalling
port can only be done if the port is currently disconnected.
(no subject)
On Tue, Feb 7, 2012 at 10:30 AM, Sylvain Joyeux <sylvain [dot] joyeux [..] ...> wrote:
> On 02/06/2012 10:28 PM, Peter Soetens wrote:
>>>
>>> I still have a question about the RemoteChannelElement. Is there any
>>> method
>>> that is always called at connection time, where we could call
>>> propagateNeedsSignal for caching its return value ?
>
> Since propagateNeedsSignal is recursive, you will need to add the call to
> propagateNeedsSignal separately inside the connection logic (otherwise,
> every ready() calls will call propagateNeedsSignal recursively ... not very
> nice). Or "fuse" it in the current ready() call.
It was a typo from my part. There is a difference between ready() and
channelReady(). The former is user API,
the latter is called once when the connection is complete -> so this
is where you
can do the check, so not in ready() what I wrote before.
>
>
>>> There is a last point to discuss : in addition to caching the return
>>> value of
>>> propagateNeedsSignal upon connection, I would like to update this value
>>> when
>>> signalInterface is called. Is it a good idea ? Is there other functions
>>> that
>>> can change this value ?
>>
>>
>> signalInterface is currently only called by the data flow interface to
>> tell the port
>> it has been added as an event port. After that, it is never called
>> anymore by RTT.
>> Since this is a public function a user could try to call this function
>> as well, in which
>> case our behavior would no longer match. I'd prefer to make
>> DataFlowInterface
>> a friend of InputPortInterface and make signalInterface
>> protected/private, instead of
>> trying to work around incorrect use of the API.
>
> Just for my information, what is the signalInterface ? Originally, the port
> was generating an event... Provided that it is still actual (I sure hope it
> is since it is something I was planning to build upon), I personally think
> that the signalling behaviour should work as soon as this event is created.
> Which can be done by the user. However, I believe that we can mandate that
> the change from non-signalling to signalling port can only be done if the
> port is currently disconnected.
Just like you are chasing to improve Port compilation times and memory
sizes, we have done so as
well by removing the 'multiple callback' feature from the InputPortInterface
and support only one callback, such that Event<> is no longer needed, and the
callback can be stored in theTaskContext (dataOnPortCallback) instead
of in the port.
So one callback for one port. If you need more, do your own
demultiplexing in that callback.
The 'old' event can be enabled by defining ORO_SIGNALLING_PORTS, but this was
for transitional purposes.
Peter
(no subject)
On 02/07/2012 10:41 AM, Peter Soetens wrote:
> So one callback for one port. If you need more, do your own
> demultiplexing in that callback.
Ah. I missed that one. Thanks for the info. Do you have any figures in
the associated gain ?
(no subject)
2012/2/7 Sylvain Joyeux <sylvain [dot] joyeux [..] ...>:
> On 02/07/2012 10:41 AM, Peter Soetens wrote:
>>
>> So one callback for one port. If you need more, do your own
>> demultiplexing in that callback.
>
> Ah. I missed that one. Thanks for the info. Do you have any figures in the
> associated gain ?
Not anymore, but I did check the numbers back then. (maybe there's a
trace on the ML).
Your changes to remove the operations are having more effect though.
We're now mainly
playing with extern template definitions to speed up compiling or
reduce code size. The
problem is that the gnu/gold linkers are quite fragile and sometimes
break what works,
so we're using it quite conservatively. For example, on Ubuntu Lucid,
ld was doing a good job.
Peter
(no subject)
On 02/07/2012 11:01 AM, Peter Soetens wrote:
> Not anymore, but I did check the numbers back then. (maybe there's a
> trace on the ML).
>
> Your changes to remove the operations are having more effect though.
Yes. Unfortunately, it's only valid on a non-internal-scripting
scenario. Not really your use case.