Problem with RRT*-Planner (only at benchmarking) since MoveIt!-release

867 views
Skip to first unread message

Dominik Kisskalt

unread,
May 16, 2013, 2:22:28 PM5/16/13
to moveit...@googlegroups.com
Hello,

after setting up a new Warehouse Database, following Ioan's constructions, RVIZ-Moveit-Plugin works fine again.
But I noticed some changes concerning RRT*, which cause problems for me.
At first I have a general question, then I noticed the benchmark-tool doen't work with standard-params for RRT*
and at least I noticed a bug in MoveIt Rviz-Plugin.

1.
When I select RRTStarkConfigDefault for planning inside RVIZ it executed while always taking the maximum allowed time. (I think this is wanted when I interpret the description on http://ompl.kavrakilab.org correctly)

[ INFO] [1368725707.525448986]: No optimization objective specified. Defaulting to optimization of path length for the allowed planning time.

I couldn't find a the valid nomination/parameter to set this "optimization objective" (and his allowed values). I looked here, but couln't find a RRT*.cpp and here (found no matching parameter-notation). Can I set this param also in the .yaml - file ?

2.
When I launch "run_benchmark_ompl.launch" all Default planners work fine except of RRT* (which is also the only one with extra params in the .yaml file by default)
Following Error occurs:

***[ INFO] [1368727189.967177175]: Planner configuration 'arm[RRTStarkConfigDefault]' will use planner 'geometric::RRTstar'. Additional configuration parameters will be set when the planner is constructed.
[ INFO] [1368727189.967630625]: No optimization objective specified. Defaulting to optimization of path length for the allowed planning time.
[ INFO] [1368727189.968036234]: Starting with 1 states
[moveit_benchmark_faps_Aspire_5740D_31153_2566901566941376198-3] process has died [pid 31193, exit code -11, cmd /opt/ros/groovy/lib/moveit_ros_benchmarks/moveit_run_benchmark /home/faps/Desktop/testtest.cfg --benchmark-planners __name:=moveit_benchmark_faps_Aspire_5740D_31153_2566901566941376198 __log:=/home/faps/.ros/log/64884ed4-be52-11e2-b7b3-00262d79481a/moveit_benchmark_faps_Aspire_5740D_31153_2566901566941376198-3.log].
log file: /home/faps/.ros/log/64884ed4-be52-11e2-b7b3-00262d79481a/moveit_benchmark_faps_Aspire_5740D_31153_2566901566941376198-3*.log

I don't understand it because inside Rviz, RRT* works correctly and according to their .launch-files they're using the same .yaml files.

3. Maybe it isn't noticed until yet: If you're renaming a scene after an already existing scene RVIZ dies after confirming the warning-message.

Thanks in advance
Dominik



Ioan Sucan

unread,
May 16, 2013, 2:29:05 PM5/16/13
to Dominik Kisskalt, moveit...@googlegroups.com
Hello Dominik,

As usual, answers inline:


On Thu, May 16, 2013 at 9:22 PM, Dominik Kisskalt <dominik....@googlemail.com> wrote:
Hello,

after setting up a new Warehouse Database, following Ioan's constructions, RVIZ-Moveit-Plugin works fine again.
But I noticed some changes concerning RRT*, which cause problems for me.
At first I have a general question, then I noticed the benchmark-tool doen't work with standard-params for RRT*
and at least I noticed a bug in MoveIt Rviz-Plugin.

1.
When I select RRTStarkConfigDefault for planning inside RVIZ it executed while always taking the maximum allowed time. (I think this is wanted when I interpret the description on http://ompl.kavrakilab.org correctly)

[ INFO] [1368725707.525448986]: No optimization objective specified. Defaulting to optimization of path length for the allowed planning time.

I couldn't find a the valid nomination/parameter to set this "optimization objective" (and his allowed values). I looked here, but couln't find a RRT*.cpp and here (found no matching parameter-notation). Can I set this param also in the .yaml - file ?


Unfortunately we do not have proper support (read: 'easy to configure') for planning with costs in the ompl_interface right now. The parameters you would set for the yaml file are considered in RRTstar, but there is no nice way of specifying a cost representation. I will need to add a plugin for this.
Perhaps submit a feature request on moveit_planners?

 
2.
When I launch "run_benchmark_ompl.launch" all Default planners work fine except of RRT* (which is also the only one with extra params in the .yaml file by default)
Following Error occurs:

***[ INFO] [1368727189.967177175]: Planner configuration 'arm[RRTStarkConfigDefault]' will use planner 'geometric::RRTstar'. Additional configuration parameters will be set when the planner is constructed.
[ INFO] [1368727189.967630625]: No optimization objective specified. Defaulting to optimization of path length for the allowed planning time.
[ INFO] [1368727189.968036234]: Starting with 1 states
[moveit_benchmark_faps_Aspire_5740D_31153_2566901566941376198-3] process has died [pid 31193, exit code -11, cmd /opt/ros/groovy/lib/moveit_ros_benchmarks/moveit_run_benchmark /home/faps/Desktop/testtest.cfg --benchmark-planners __name:=moveit_benchmark_faps_Aspire_5740D_31153_2566901566941376198 __log:=/home/faps/.ros/log/64884ed4-be52-11e2-b7b3-00262d79481a/moveit_benchmark_faps_Aspire_5740D_31153_2566901566941376198-3.log].
log file: /home/faps/.ros/log/64884ed4-be52-11e2-b7b3-00262d79481a/moveit_benchmark_faps_Aspire_5740D_31153_2566901566941376198-3*.log

I don't understand it because inside Rviz, RRT* works correctly and according to their .launch-files they're using the same .yaml files.

This sounds like perhaps there is a configuration error. In any case, the code should not crash. Could you post this as a bug on moveit_ros, with instructions on how to reproduce?
 
3. Maybe it isn't noticed until yet: If you're renaming a scene after an already existing scene RVIZ dies after confirming the warning-message.

This is definitely a bug. Could you post this as a bug as well?

Sorry my answers are not so helpful. The bugs will be fixed soon though :)

Ioan
 
Thanks in advance
Dominik




Dominik Kisskalt

unread,
May 16, 2013, 3:41:44 PM5/16/13
to moveit...@googlegroups.com, Dominik Kisskalt
Hallo Ioan,

thanks for your Answer. As desired I created the two bugs.

Many thanks in advance for fixing the bugs "soon" ;)
Dominik

Dominik Kisskalt

unread,
May 20, 2013, 11:25:52 AM5/20/13
to moveit...@googlegroups.com, Dominik Kisskalt
Hello again,

I installed the newest ompl-branch on the "raw"-way with success.

But RRT* and PRM does not seem to work well. (All my Params in ompl_planning.yaml are on default values)
I try to discribe the problems. perhaps they have the same background.

 -  RRT* is very often not able to find a solution (planning time 10 sec) also for very simple problems. This was before MoveIt! - Release different.
 -  sometimes the planning-process stops with no real error-message but complaining about a "double free or corruption" :

[ INFO] [1369058196.513452739]: Planning request received for MoveGroup action. Forwarding to planning pipeline.
[New Thread 0x7fffb7fff700 (LWP 9291)]
[ INFO] [1369058196.520177759]: Planner configuration 'arm[RRTStarkConfigDefault]' will use planner 'geometric::RRTstar'. Additional configuration parameters will be set when the planner is constructed.
[ INFO] [1369058196.520589112]: No optimization objective specified. Defaulting to optimization of path length for the allowed planning time.
[ INFO] [1369058196.520967061]: Starting with 1 states
[Thread 0x7fffb7fff700 (LWP 9291) exited]
[ INFO] [1369058206.569181670]: Created 854 states. Checked 38022 rewire options.
[ INFO] [1369058206.569269353]: Solution found in 10.048678 seconds
*** glibc detected *** /opt/ros/groovy/lib/rviz/rviz: double free or corruption (fasttop): 0x00000000014e8a10 ***

- PRM works only in 1 of 10 cases. The other 9, one of the two following exceptions are thrown:

 [New Thread 0x7fffb3fff700 (LWP 8357)]
[ INFO] [1369057949.069301582]: Planner configuration 'arm[PRMkConfigDefault]' will use planner 'geometric::PRM'. Additional configuration parameters will be set when the planner is constructed.
move_group: malloc.c:2451: sYSMALLOc: Assertion `(old_top == (((mbinptr) (((char *) &((av)->bins[((1) - 1) * 2])) - __builtin_offsetof (struct malloc_chunk, fd)))) && old_size == 0) || ((unsigned long) (old_size) >= (unsigned long)((((__builtin_offsetof (struct malloc_chunk, fd_nextsize))+((2 * (sizeof(size_t))) - 1)) & ~((2 * (sizeof(size_t))) - 1))) && ((old_top)->size & 0x1) && ((unsigned long)old_end & pagemask) == 0)' failed.

Program received signal SIGABRT, Aborted.
[Switching to Thread 0x7fffd2a7b700 (LWP 8059)]
0x00007ffff4b2e425 in raise () from /lib/x86_64-linux-gnu/libc.so.6
(gdb)

Number 2:

[ INFO] [1369058465.331473463]: Planning request received for MoveGroup action. Forwarding to planning pipeline.
[New Thread 0x7fffb7fff700 (LWP 10168)]
[ INFO] [1369058465.334931730]: Planner configuration 'arm[PRMkConfigDefault]' will use planner 'geometric::PRM'. Additional configuration parameters will be set when the planner is constructed.
*** glibc detected *** /opt/ros/groovy/lib/moveit_ros_move_group/move_group: malloc(): memory corruption: 0x00007fffc01454c0 ***
[Thread 0x7fffb7fff700 (LWP 10168) exited]

Are these new problems/bugs? If not how can I fix it?
If you need further information I will give them.

Many thanks in advance
Dominik
 




Ioan Sucan

unread,
May 20, 2013, 11:38:12 AM5/20/13
to Dominik Kisskalt, moveit...@googlegroups.com
This looks interesting. I have run similar benchmarks with this code and run all planners without a crash. Could you send me your code + configuration files? Ideally with instructions on how to compile & run to replicate the bug.

Ioan

Dominik Kisskalt

unread,
May 20, 2013, 12:01:28 PM5/20/13
to moveit...@googlegroups.com, Dominik Kisskalt
I can't offer you code, because I'm not working with an IDE. I'm only using the Terminal. Or is there still an option to extract the code?
I uploaded my whole moveit-config-folder (TX60L_Final12) with .launch file (Moveit12.launch)  and urdf/mesh (learning_urdf) here.

I hope this will help you.

Dominik

Ioan Sucan

unread,
May 20, 2013, 12:14:55 PM5/20/13
to Dominik Kisskalt, moveit...@googlegroups.com
I think there is a miss-communication here. The use of an IDE should not be related with the existence of source code. I do not use an IDE either. I am assuming there is a file on your computer where you wrote code you are compiling; or are you just running things with roslaunch?
If the latter, could you tell me which commands you are running and perhaps send me the .cfg file that you pass to the benchmark code?

Dominik Kisskalt

unread,
May 20, 2013, 12:24:03 PM5/20/13
to moveit...@googlegroups.com, Dominik Kisskalt
I'm only using roslaunch.

my commands are the following:

source /opt/ros/groovy/setup.bash
    cd Desktop
    export ROS_PACKAGE_PATH=$PWD:$ROS_PACKAGE_PATH
    roslaunch MoveIt12.launch debug:=true

I think the cfg-file is in this case not important because the same issues are existing in Rviz.
Without RRT* and PRM: (for the Config see my link in the previously post)
[scene]
name=pickandplace
runs=50
timeout=30

[plugin]
name=ompl_interface/OMPLPlanner
planners=BKPIECEkConfigDefault ESTkConfigDefault KPIECEkConfigDefault LBKPIECEkConfigDefault RRTConnectkConfigDefault RRTkConfigDefault SBLkConfigDefault LazyRRTkConfigDefault

Ioan Sucan

unread,
May 20, 2013, 12:34:02 PM5/20/13
to Dominik Kisskalt, moveit...@googlegroups.com
Hello Dominik,

I think you may have not recompiled things after installing OMPL globally. Try removing your build/ and devel/ dirs, and recompile. I don't think the build system catches on to changes in globally installed files.
Things run fine for me -- I was able to run PRM and RRT* repeatedly without problems.

Ioan

Dominik Kisskalt

unread,
May 20, 2013, 1:06:10 PM5/20/13
to moveit...@googlegroups.com, Dominik Kisskalt
Sorry for this request:

Where can I find these build/ and devel/ dirs? Under /opt/ros/groovy there was none of them and under /home/faps/ompl I only found a build-directory.

Or is it possible that ROS is still using the old ompl-version?
Because when I launch:

faps@faps-Aspire-5740D:~/Desktop$ rospack find ompl

I get:

/opt/ros/groovy/share/ompl

but the new ompl-branch-files lie under /home/faps/ompl.

Many Thanks in advance
Dominik

Ioan Sucan

unread,
May 20, 2013, 1:16:15 PM5/20/13
to Dominik Kisskalt, moveit...@googlegroups.com
With the new version of OMPL you cannot run from debs. You need to recompile moveit from source.

If you run from debs there are no build/ and devel/ folders.

Ioan

Dominik Kisskalt

unread,
May 20, 2013, 4:51:56 PM5/20/13
to moveit...@googlegroups.com, Dominik Kisskalt
Am I right with my suggestion that "recompile" means "catkin_make".
Unfortunately catkin_make fails at 73% :

Linking CXX shared library /home/faps/moveit/devel/lib/libmoveit_move_group_default_capabilities.so
[ 72%] Built target moveit_move_group_default_capabilities
make: *** [all] Error 2
Invoking "make" failed

I read that I have to delete the "debian headers" in this case.
Are these in this the folder: "/opt/ros/groovy/include/moveit"?

Dominik Kisskalt

unread,
May 26, 2013, 2:15:24 PM5/26/13
to moveit...@googlegroups.com, Dominik Kisskalt
Hello again.

In my previous post I answered myself ;) and after deleting this folder it worked.

I recognized RRT* is mostly not able to solve problems with obstacles in the way.
Does this occur because I'm working with queries and not goal constraints?
Or because I'm not setting a tolerance? ( Or both? )

Is there a way to set up goal constraints inside the RVIZ MoveIt! plugin?
@ Ioan            I'm trying to readjust what you did in this paper. (the display of the goal constraints)

Thanks in advance
Dominik

Ioan Sucan

unread,
May 26, 2013, 2:34:33 PM5/26/13
to Dominik Kisskalt, moveit...@googlegroups.com
Hello Dominik,

I am not sure what you mean when you say query as opposed to goal constraints. A query consists of a start state + goal representation. Goal constraints is how goals are defined in moveit, so goal constraints are always part of a query.
The tolerance should not affect how the algorithm works. I think things should work with default tolerances. Does RRT or RRTConnect solve the problem for you?

Also, if you are running OMPL from source, please update your installation (some fixes were committed today)

Ioan

Dominik Kisskalt

unread,
May 26, 2013, 3:40:22 PM5/26/13
to moveit...@googlegroups.com, Dominik Kisskalt
Hello Ioan,

yes RRT and RRTConnect can solve the problems, but compared to SBL, EST or KPIECE they are quiet weak (time, solve-ratio)

I'm trying to accomplish that only the position (in a boundingbox) and rotation of the endeffector is given as gaol-constraints and not a complete Robot-state (such as in the pr2-tutorial for RVIZ MoveIt! Plugin).
How can I set this in RVIZ MoveIt Plugin up and use it in the bechmark-tool?

Thanks in advance
Dominik


Ioan Sucan

unread,
May 26, 2013, 3:59:46 PM5/26/13
to Dominik Kisskalt, moveit...@googlegroups.com
Hello Dominik,

What you need to do is save the set of constraints you would like to apply to the moveit warehouse. The benchmark GUI is not entirely ready for prime time, but the benchmarking back-end works fine.
You should look at this tutorial:
http://moveit.ros.org/wiki/index.php/Groovy/Benchmarking

You should also look at the moveit_ros_warehouse package and initialized_demo_db.cpp for an example of how to fill in the database of constraints.

Ioan

Dominik Kisskalt

unread,
May 26, 2013, 4:33:51 PM5/26/13
to moveit...@googlegroups.com, Dominik Kisskalt
Thank You,

do you know if the benchmarkresults (like planning time, path_length) with constraints only for the end effector differ (qualitative not quantitative) much from these one with queries?

If yes: Are the bechmark-results of the planning-arena-website still relevant and comparable with results of the current status of ompl?

Thank You in advance
Dominik

Ioan Sucan

unread,
May 26, 2013, 4:38:31 PM5/26/13
to Dominik Kisskalt, moveit...@googlegroups.com
On Sun, May 26, 2013 at 11:33 PM, Dominik Kisskalt <dominik....@googlemail.com> wrote:
Thank You,

do you know if the benchmarkresults (like planning time, path_length) with constraints only for the end effector differ (qualitative not quantitative) much from these one with queries?

If you mean the goal being specified as PoseConstraints rather than JointConstraints, the difference is just a few IK calls, so no real difference.
If you mean path constraints, there will be significant differences (planning with path constraints will be slower)

If yes: Are the bechmark-results of the planning-arena-website still relevant and comparable with results of the current status of ompl?

plannerarena.org currently only includes results from SE2 and SE3 environments, nothing for the PR2 yet.
The results on the website are relevant and should be very similar to the current status of ompl.

Ioan

Dominik Kisskalt

unread,
May 26, 2013, 4:46:06 PM5/26/13
to moveit...@googlegroups.com, Dominik Kisskalt
Thank you very much. Now I know I can skip setting up Pose-Constraints.

Out of curiosity: Do you know when the bechmark-gui is available?
Reply all
Reply to author
Forward
0 new messages