Closed ahoarau closed 6 years ago
So you want to be able to control when the RSI
motion correction becomes active and exits? There are several ways I can think of off the top of my head to accomplish this but all require RSI
knowledge and modification of the RSI
signal flow configuration.
Can you elaborate a bit on what you want?
FYI:
; MOVECORR() # Then how to exit this function ?
RSI
requires a KRL
"motion" to be active to actually apply updates. The MOVECORR()
function is a special "move" command that results in no KRL
motion but applies RSI
offsets. This function blocks until a fault or the RSI context issues a stop via the STOP
object in the signal flow. You can think of it as a synchronous spinner.
Thank for your input. I have managed to integrate an exit via RSIVisual (STOP block connected to the 8th otuput of the Ethernet bloc), and then I have to send an extra boolean to the RSICommand XML that I'm sending (something like ...<s>true</s></Sen>
).
So you want to be able to control when the RSI motion correction becomes active and exits? There are several ways I can think of off the top of my head to accomplish this but all require RSI knowledge and modification of the RSI signal flow configuration.
Exactly.
What I expect with a robot from an external computer is as simple as :
MOVECORR
functionExample : simple pick and place with visual servoing. All of that from an external computer. PTP to a few points, then movecorr to adjust, then some more PTPs, but all of that from an external computer.
I wish there would be a bloc called PTP in RSIVisual ( just like the axiscorr bloc) so I could just execute a PTP motion 1) Without having to interpolate/control it myself between two points (BIG issue) 2) At higher speed than the max allowed by RSI movecorr (there is a limit that is much lower than T1/T2 max speed, even with maxCorr settings to a high value) (not so big of an issue, but still important)
@ahoarau wrote:
At higher speed than the max allowed by RSI movecorr (there is a limit that is much lower than T1/T2 max speed, even with maxCorr settings to a high value) (not so big of an issue, but still important)
this surprises (and confuses) me: RSI should allow you to use 100% of the robots capabilities wrt motion velocity. Are you saying that you can't achieve that?
How are you generating the trajectories?
You may actually be interested in #110.
You may actually be interested in #110.
Thanks for the info. I thought it could be interesting but in the end you still need to create your own way of sending joint commands :
and then in KRL something like :
SWITCH EKI_GetInt("Robot/Mode") :
case 1:
ptp_cmd.A1 = EKI_GetReal("Robot/A1Command")
ptp_cmd.A2 = ...
...
BAS(#ACC_PTP , $acc_from_eki )
BAS(#VEL_PTP , $vel_from_eki )
PTP ptp_cmd
EKI_SetBool("Robot/MoveDone",True)
Which I guess can be done by playing with the variables $SEN_PINT
and $SEN_PREA
in RSI.
this surprises (and confuses) me: RSI should allow you to use 100% of the robots capabilities wrt motion velocity. Are you saying that you can't achieve that?
The robot is vibrating a lot if using the absolute mode (T1/T2, IPO/IPO FAST). Smooth when using relative, but limited by gear torque apparently (happended a lot in T1, I was getting the Gear Torque exceeded error even though the movement was super slow).
How are you generating the trajectories?
KDL for now.
I mentioned #110 as it is a similar interface as RSI, but with less strict real-time requirements. I'm assuming that if you don't need the real-time bandwidth and very precise control of RSI, EKI might be enough for you, especially if you're ok with letting PTP
and LIN
do the interpolation for you.
I thought it could be interesting but in the end you still need to create your own way of sending joint commands
well, yes. It's only a driver, so it will need your input to tell it what to make the robot do.
and then in KRL something like
I'm still a bit confused why you'd want to do this with RSI, but nevermind that.
The robot is vibrating a lot if using the absolute mode (T1/T2, IPO/IPO FAST). Smooth when using relative, but limited by gear torque apparently (happended a lot in T1, I was getting the Gear Torque exceeded error even though the movement was super slow).
This sounds like lost packets / non-smooth trajectories / wrong payload settings to me.
RSI is specifically designed to allow external access to and control of the full robot capabilities, so I would suspect something not being completely ok on the side that generates the trajectories or controls the 'playout'.
KDL for now.
That is a bit vague: are you manually interpolating between joint poses, using some kind of trajectory (spline) generator, something else?
I managed to do this in the past with the FRI (lwr 4+), and KukaVarProxy, but the communication is really random.
@ahoarau thoughts on this? Any updates?
Sorry about the late answer.
This sounds like lost packets / non-smooth trajectories / wrong payload settings to me.
RSI is specifically designed to allow external access to and control of the full robot capabilities, so I would suspect something not being completely ok on the side that generates the trajectories or controls the 'playout'.
After running many more tests : ABSOLUTE
makes the robot vibrate. RELATIVE
is working great but you have to make sure that you have minimum jitter in the comm (which leads to jerky trajectory --> jerky robot movements --> torque error). Tested with IPO
and IPO_FAST
.
I managed to do this in the past with the FRI (lwr 4+), and KukaVarProxy, but the communication is really random.
KukaVarProxy allows to set any KRC variable directly, so it's quite easy to setup a mode switching script.
FRI allows users to send a double[]
, int[]
and bool[]
that you can access in the KRL code. So basically you have to do you own comm on the KRL side (ex, if bool[0] is true, siwtch to mode 1 and so on).
RSI is quite similar as FRI (you can full $SEN_PINT and $SEN_PREA from the remote computer), but I could not manage yet to access $SEN_PREA
and $SEN_PINT
in the KRL code (in RSI Visual you can create the link between the Ethernet block to this tab via the MAP_TO_REA
but again it seems to stay inside the RSI context, i.e not interaction with the rest of the KRL code).
Anyway a mix between KVP and RSI seem to do the trick for now. Thanks for you help :)
Hello, I'm just getting started with the RSI, so forgive me if my question is really basic. I've successfully integrated/moved the robot with the
joint_trajectory_controller
, but now I'd like to add a bit some functionality to the KRL script. I would like to be able to set variables within the KRL script using the RSI, for example to implement a switch case scenario.Example :
I managed to do this in the past with the FRI (lwr 4+), and
KukaVarProxy
, but the communication is really random. If you guys have any tips/examples on how to implement this with RSI, I would be extremely grateful as I spent too many hours not understanding the provided RSI docs. Thanks in advance !