hungpham2511 / toppra

robotic motion planning library
https://hungpham2511.github.io/toppra/index.html
MIT License
625 stars 170 forks source link

AttributeError: 'NoneType' object has no attribute 'get_duration' #26

Closed JadBatmobile closed 4 years ago

JadBatmobile commented 5 years ago

Hello,

I posted about an issue eariler this week with regards to durations that were less than 0.2, the problem was a numerical conditioning one and it was solved by cloning in the newest repo.

However, another problem is occuring with the newest repo,

I am getting a AttributeError: 'NoneType' object has no attribute 'get_duration' error when the input waypoints are all very close to one another. The following function is what im using:

def toppra_constant_time(way_pts, am, vm, duration):

path = ta.SplineInterpolator(np.linspace(0, 1, way_pts.shape[0]), way_pts)
vlim_ = np.ones(3) * vm
vlim = np.vstack((-vlim_, vlim_)).T
# Create acceleration bounds, then acceleration constraint object
alim_ = np.ones(3) * am
alim = np.vstack((-alim_, alim_)).T
pc_vel = constraint.JointVelocityConstraint(vlim)
pc_acc = constraint.JointAccelerationConstraint(
    alim, discretization_scheme=constraint.DiscretizationType.Interpolation)

# Setup a parametrization instance with hot-qpOASES
instance = algo.TOPPRAsd([pc_vel, pc_acc], path, gridpoints=np.linspace(0, 1, 51),
                         solver_wrapper='hotqpoases')

instance.set_desired_duration(duration)

# Retime the trajectory, only this step is necessary.
jnt_traj, aux_traj = instance.compute_trajectory(0, 0)

ts_sample = np.linspace(0, jnt_traj.get_duration(), 100)
jt = jnt_traj.eval(ts_sample)

print jt
qs_sample = jnt_traj.evaldd(ts_sample)
vel_sample = jnt_traj.evald(ts_sample)

'''
a1 = [i[0] for i in jt]
a2 = [i[1] for i in jt]
a3 = [i[2] for i in jt]
plot_angles(a1, a2, a3, ts_sample)
'''

return duration, jt, vel_sample, qs_sample, ts_sample

The jnt_traj is being returned as None. The input is (for three joints):

`way_pts: [[-0.00038593 -0.00038593 -0.00038593] [ 0.00013093 0.00013093 0.00013093] [ 0.00064752 0.00064752 0.00064752] [ 0.00116383 0.00116383 0.00116383] [ 0.00167987 0.00167987 0.00167987] [ 0.00219563 0.00219563 0.00219563] [ 0.00271112 0.00271112 0.00271112] [ 0.00322633 0.00322633 0.00322633] [ 0.00374127 0.00374127 0.00374127] [ 0.00425594 0.00425594 0.00425594]]

am = 100 vm = 100 duration = 0.5`

JadBatmobile commented 5 years ago

I will be commanding very small trajectories, so i will revert to using the older version of toppra, until this is hopefully fixed.

Thank you :)

pbeeson commented 5 years ago

Let me start by saying that, all in all, toppra is the best solution to this problem that I've found, but it does still have issues with dense trajectories or near-zero trajectories that are > size 2 in length.

I also use toppra a lot, and have a collection of trajectories that have caused problems with toppra in the past. The newest versions of toppra fail on some of these specific examples (especially with the auto scaling turned on), while a specific frozen fork that I have (that also includes some of my own minor changes) does work for the collection. Last night, a customer filed an issue with me that I tracked down to a new case not handled by my fork, so I had to make some change on my pre-conditioning of the trajectory that I send to handle this specific case. If you are interested, I can point you to my "pre-toppra" python code and fork that I've been using for dense trajectories with potentially very small delta between successive waypoints.

I will also add your example above to the test collection to see how my fork and pre-conditioning handle it.

JadBatmobile commented 5 years ago

Hey Patrick, thanks for the quick response!

if your fork can handle the function i pasted above, i will surely try it on my system!

Let me know :+1: :)

pbeeson commented 5 years ago

It does, but before that, have you simply tried doing something like the below? This seems to handle your case in my fork, and only really adds a few milliseconds to run multiple times.

    scalar = 1
    data = None
    while data is None and scalar < 10000:
        way_pts2 = way_pts*scalar
        max_vel2 = max_vel*scalar
        max_acc2 = max_acc*scalar
        data = run_optimization(way_pts2, max_vel2, max_acc2, desired_time)
        scalar = scalar*10

If you scale the waypoints the same as the velocities and accelerations, you will get back the same times, since you are just changing the base units.

pbeeson commented 5 years ago

Note: edited the pseudocode above as it was buggy (even for example code)

hungpham2511 commented 5 years ago

Thanks, guys for reporting these issues. Sometimes ago I thought re-scaling problem would fix this numerical issue, but turn out it clearly does not :(

Patrick, I really appreciate your invaluable feedbacks. This test suite contains a few test instances with very small, (zero motion), but it apparently misses out many situations, which you guys are reporting.

https://github.com/hungpham2511/toppra/blob/master/tests/retime/test_zero_motions.py

It it possible that you share your test collections with us so that I have a better idea what kinds of problems you have facing?

hungpham2511 commented 5 years ago

@JadBatmobile I can solve your instance with the latest commit.

figure_1-7

I think the problem is with the QP solver. Do you have qpoases installed?

JadBatmobile commented 5 years ago

@pbeeson When you scale your waypoints, are you not changing the entire path..?

@hungpham2511 I do have qpoases installed, im trying to run another optimization, very small trajectory, same code as above with the following inputs:

way_pts: [[-3.85929168e-04 -3.85929168e-04 -3.85929168e-04] [-2.13610365e-04 -2.13610365e-04 -2.13610365e-04] [-4.13223272e-05 -4.13223272e-05 -4.13223272e-05] [ 1.30934967e-04 1.30934967e-04 1.30934967e-04] [ 3.03161539e-04 3.03161539e-04 3.03161539e-04] [ 4.75357412e-04 4.75357412e-04 4.75357412e-04] [ 6.47522605e-04 6.47522605e-04 6.47522605e-04] [ 8.19657141e-04 8.19657141e-04 8.19657141e-04] [ 9.91761041e-04 9.91761041e-04 9.91761041e-04] [ 1.16383433e-03 1.16383433e-03 1.16383433e-03]] am = 2000 vm = 2000 duration = 0.1

This gives me the NoneType error once again

pbeeson commented 5 years ago

It it possible that you share your test collections with us so that I have a better idea what kinds of problems you have facing?

Yeah, I'll get you my test.py script soon. Note that I always use Seidel and I always enforce clamping because I need the final point to be guaranteed v=0. You can then try turning on/off auto scaling (it never made it through all my collection in the past).

JadBatmobile commented 5 years ago

@pbeeson

After scaling, i have to divide the output trajectory joint values by the scalar value obviously, correct?

pbeeson commented 5 years ago

When you scale your waypoints, are you not changing the entire path..?

By scaling the waypoint and velocites and accelerations by the same number, you are just changing the units. Of course, you need to divide that scalar back out on any returned waypoints, velcocites, and accelerations you get out of the solver. But the times will be correct.

JadBatmobile commented 5 years ago

right, just wanted to make sure before deploying! I think this is a good solution for now... i struggle with the theoretical causes of this problem, if anyone cares to shed light that would be good. P.S. i did read the toppra paper

pbeeson commented 5 years ago

@hungpham2511 Attached is my test program that collects waypoints, velocities, and accelerations that we've seen bomb toppra in the past. If you notice on line 103, there is a while loop that does exactly what I mentioned to @JadBatmobile above. If you make that while False and ... to ignore it, then you'll see it bomb out on the first problem set, which happens to be the one from the top of this thread. toppra_call.py.zip

pbeeson commented 5 years ago

I do not know if the script above works for the current toppra, as I am running this against my fork that ensures things like 0 motion between successive waypoints results in 0.001 second times.

hungpham2511 commented 5 years ago

@pbeeson Thanks for the test cases.

I remember we discussed on another issue thread about your requirements. They are:

  1. zero-motion trajectories should be parametrized to have 0.001 second duration
  2. start and final joint velocity should be zero? Do you have any other requirements, e.g. computation time, etc?

Honestly, I find both requirements are quite reasonable, and TOPP-RA should satisfy it without any modifications. Will figure out something.

@JadBatmobile I fail to solve the new example you gave. The underlying problem is that the joint values vary too little (1e-4 order) comparing to the change in path position (fixed at 1). This causes the optimization problems toppra solves at each instance to be badly scaled and hence failed to solve.

@pbeeson solution is really neat. I have tried scaling the path position before, but have not tried scaling the joint values and velocity. Let's see if we can implement this functionality in toppra.

pbeeson commented 5 years ago

zero-motion trajectories should be parametrized to have 0.001 second duration

They should have non-zero duration. Ideally at most 1 ms. If it was 1e-4 that would be fine too, so long as it’s not zero.

Although I guess zero would be ok too since that’s catchable in post-processing. But > 0.001 seems too long for a zero motion waypoint.

github-actions[bot] commented 4 years ago

Stale issue message