Open rdiankov opened 12 years ago
Changed 5 months ago by rdiankov
cuong found the library:
it needs DH parameters, so will add code to output them. Changed 5 months ago by rdiankov
code added in r3178:
dhparameters = planningutils.GetDHParameters(robot)
Changed 5 months ago by rdiankov
Just updated an example that shows how to get parabolic timing between two configurations without checking collisions:
http://openrave.org/en/main/tutorials/openravepy_examples.html#parabolic-retiming
The waypoints of the trajectory will be where the linear/parabolic segment switches occur. Changed 5 months ago by rdiankov
the best canonical demos to test with are: in openrave to use:
openrave.py --example hanoi openrave.py --example graspplanning
but this requires first implementing a Planner and putting your smoothing/retiming code in there, which could be a little involved, i'll help with this once we know your algorithm is working. the most easiest next step is to use this example:
http://openrave.org/en/main/tutorials/openravepy_examples.html#returning-a-trajectory
you'll notice it returns a "traj" object, which you can get the waypoints from and feed to your retiming algorithms. Once you have timestamps and new waypoints, create a new openrave trajectory and then run it with
robot.GetController().SetPath(newtraj)
Creating a trajectory first requires to create the specification. There's an quick way to do this where you fill joint values + velocities + delta timestamps:
newtraj = RaveCreateTrajectory(env,'') g=robot.GetActiveConfigurationSpecification().GetGroupFromName('joint_values') g.interpolation='linear' spec = ConfigurationSpecification() spec.AddGroup(g) spec.AddVelocityGroups(True) newtraj.Init(spec)
You can check the spec with "print spec" to see what are the indices for the values. Then to add a point do:
newtraj.Insert(index,pointdata)
follow-up: ↓ 6 Changed 5 months ago by rdiankov
In response to Cuong's minimum time code:
Now we need to start cleaning it up and use the existing c++ functionality as much as possible. several places that stand out:
Shortcutting.Smooth - it looks like you shortcut with straight line segments? do you think results would improve if using parabolic segments? There's a very simple example of computing the best parabolic segment:
http://openrave.org/en/main/tutorials/openravepy_examples.html#parabolic-retiming
LineCollisionChecking? - there's a C++ class for this given two configurations a and b. If using it, eventually it will be replaced with the exact collision checking stuff we talked about previously.
trajectory interpolation/running/resampling - openrave has many facilities of this using the openravepy.Trajectory class.
implement the corke dynamics into c++ and allow people to use it through the KinBody? class. By the way, what is there a better termination condition than n_steps?
By using this functionality, it will become possible to replace the default smoother (implemented as a Planner interface) for every openrave demo transparently!
Several questions:
how are max torques implemented right now? constant or varying with respect to current velocity? In fact, when I we think about it. Most motors are rated with max power (watts).
in reply to: ↑ 5 ; follow-up: ↓ 7 Changed 5 months ago by quangounet
* Shortcutting.Smooth - it looks like you shortcut with straight line segments? do you think results would improve if using parabolic segments? There's a very simple example of computing the best parabolic segment:
http://openrave.org/en/main/tutorials/openravepy_examples.html#parabolic-retiming
No, I'm currently interpolating with 3rd-degree polynomials in joint space. But I think 2nd-degree polynomials (parabolas) should be OK also. I'm not sure computing optimal piecewise-parabolic segments with max acceleration and max velocity would help because these max values will be superseded later in the dynamics retiming.
* LineCollisionChecking? - there's a C++ class for this given two configurations a and b. If using it, eventually it will be replaced with the exact collision checking stuff we talked about previously.
We would need PathCollisionChecking?. The Hauser paper adapts the original exact line-collision-checking to piecewise-parabola-collision-checking.
* trajectory interpolation/running/resampling - openrave has many facilities of this using the openravepy.Trajectory class.
* implement the corke dynamics into c++ and allow people to use it through the KinBody? class. By the way, what is there a better termination condition than n_steps?
Yes, I'm cleaning the source code right now. You talked about some automated ways of testing inverse dynamics. What is it about?
n_steps: In which part?
* how are max torques implemented right now? constant or varying with respect to current velocity? In fact, when I we think about it. Most motors are rated with max power (watts).
Right now I'm using constant max torques. However implementing velocity-and-acceleration-dependent max torques requires only minimum changes in the code. in reply to: ↑ 6 ; follow-up: ↓ 8 Changed 5 months ago by rdiankov
No, I'm currently interpolating with 3rd-degree polynomials in joint space. But I think 2nd-degree polynomials (parabolas) should be OK also. I'm not sure computing optimal piecewise-parabolic segments with max acceleration and max velocity would help because these max values will be superseded later in the dynamics retiming.
you are right, 3rd degree should work better.
We would need PathCollisionChecking?. The Hauser paper adapts the original exact line-collision-checking to piecewise-parabola-collision-checking.
Given that the minimum dynamic time algorithm is already discretizing the trajectory (0.01s intervals), we just need to check the straight line segments for adjacent points. If the algorithm computed a mathematical solution, then we would need something very fancy.
Anyway, we could be doing a much better job of that too ;0)
The current C++ class is called LineCollisionConstraint?:
http://openrave.org/en/coreapihtml/classOpenRAVE_1_1planningutils_1_1LineCollisionConstraint.html
I'll work on python bindings for it.
Yes, I'm cleaning the source code right now. You talked about some automated ways of testing inverse dynamics. What is it about?
i'll do the corke stuff, it requires pretty advanced knowledge of openrave internals.
the openravepy.Trajectory class usage should be straight forward thorugh.
n_steps: In which part?
In RobotDynamicsTraj?.compute_torques, you always iterate a constant amount of time. Instead I would like to iterate until the max deviation error is below some epsilon threshold.
Right now I'm using constant max torques. However implementing velocity-and-acceleration-dependent max torques requires only minimum changes in the code.
ok, great. looking forward that.
i'll also build a dynamic barrett wam model tonight. in reply to: ↑ 7 Changed 5 months ago by rdiankov
Anyway, we could be doing a much better job of that too ;0)
could be doing a better job of line collision checking follow-up: ↓ 10 Changed 5 months ago by rdiankov
Actually for industrial robots we have to convert the final trajectories to parabolic ramps anyway, so we should also make it possible to do parabolic segment shortcutting within the dynamic time minimization (Shortcutting.Smooth) in reply to: ↑ 9 Changed 5 months ago by quangounet
Replying to rdiankov:
Actually for industrial robots we have to convert the final trajectories to parabolic ramps anyway, so we should also make it possible to do parabolic segment shortcutting within the dynamic time minimization (Shortcutting.Smooth)
Even if we use parabolic ramps in the shortcutting, the retiming procedure will destroy the "parabolic" property (the path will remain that of a piecewise parabola but the trajectory will not). So anyway we will have to reconvert to parabola at the end before exporting to industrial robots. Changed 4 months ago by rdiankov
inverse dynamics computations available in r3314 as
torques=KinBody?.ComputeInverseDynamics?(dofaccel) Changed 4 months ago by rdiankov
here's another interesting paper cuong pointed out,
http://www.golems.org/papers/KunzRSS12-Trajectories.pdf
it outputs parabolic arcs with the dynamics smoothing from bobrow and slotine et al.
I've just added the new version of the mintime algorithm to master, cf. folder sandbox/mintime/
To see the algorithm at work, run the following test files:
The reference papers for the algorithms can be found here
Please play around with the test files and report the bugs :)
Todo:
was able to run the samples without any problems! not sure why but the RRT was really slow.
have you done experiments with 6 axis robots?
i can start working on more tighter c++ integration now!
by the way, would you like to advertise this functionality on the openrave-users list?
Current Structure:
Initialize Traj with parabolic segments assuming 0 velocity at inital waypoints.
Hauser ParablicRamp?: SolveMinTimeBounded?, SolveMinAccelBounded? (create python bindings)
Requirements:
Using openrave KinBody? values:
GetDOFLimits, GetDOFVelocityLimits, GetDOFAccelerationLimits, GetDOFTorqueLimits, Link.GetLocalMassFrame?, Link.GetPrincipalMomentsOfInertia?, Link.GetTransform?, Link.GetMass? Can compute jacobians for KinBody?: CalculateJacobian?, CalculateAngularVelocityJacobian?, CalculateRotationJacobian? KinBody?.CheckSelfCollision?, Environment.CheckCollision?
Verifying Trajectories
Trajectory XML
Rosen: