0
$\begingroup$

Rosanswers logo

Hi all,

I am facing a strange problem. I am using ROS move_base and SBPL for motion-primitive-based path planning. I have generated some motion primitives for SBPL and everything works fine using my laptop (Intel i5, Ubuntu 14.04). The robot plans the path and moves fine along the path.

Now I am using the very same modules (and configs) on my Odroid U3 (ARM quadcore) and it cannot find a solution. Top shows that the core is at 100%. Here is the output from move_base

[ INFO] [1412691428.999248673]: Using plugin "obstacle_layer"

[ INFO] [1412691429.127272381]: Subscribed to Topics:

[ INFO] [1412691429.172789423]: Using plugin "inflation_layer"

[ INFO] [1412691429.443358089]: Name is SBPLLatticePlanner

[ INFO] [1412691430.931921673]: Planning with ARA*

[ INFO] [1412691430.932365757]: [sbpl_lattice_planner] Initialized successfully

[ INFO] [1412691430.989290632]: Using plugin "obstacle_layer"

[ INFO] [1412691431.241103424]: Subscribed to Topics:

[ INFO] [1412691431.286346674]: Using plugin "inflation_layer"

[ INFO] [1412691431.688199674]: Created local_planner base_local_planner/TrajectoryPlannerROS

[ INFO] [1412691431.732307049]: Sim period is set to 0.10

[ INFO] [1412691432.897083008]: odom received!

[ INFO] [1412691492.209781994]: [sbpl_lattice_planner] getting start point (3.48925,-0.84064) goal point (2.00517,-1.3133) [ INFO] [1412691502.490063749]: Solution not found

[ WARN] [1412691502.492333249]: Map update loop missed its desired rate of 2.0000Hz... the loop actually took 10.0025 seconds

[ INFO] [1412691502.492543791]: [sbpl_lattice_planner] getting start point (3.48925,-0.84064) goal point (2.00517,-1.3133)

[ INFO] [1412691512.771037004]: Solution not found

I am using the following repos of the modules:

ROS indigo

sbpl_lattice_planner: https://github.com/meyerj/sbpl_lattice_planner.git

sbpl: https://github.com/sbpl/sbpl.git

Any ideas? I actually have no Idea where to start looking.

Cheers,

Markus


Originally posted by Markus Eich on ROS Answers with karma: 202 on 2014-10-07

Post score: 1

$\endgroup$

2 Answers 2

0
$\begingroup$

Rosanswers logo

The problem is the ambiguity of the char datatype. On x86 gcc it defaults to signed, on ARM to unsigned. This results in negative values getting flipped.

See here: http://www.arm.linux.org.uk/docs/faqs/signedchar.php

and here: https://github.com/sbpl/sbpl/blob/master/src/include/sbpl/discrete_space_information/environment_navxythetalat.h#L61

one solution is to simply compile with the -fsigned-char switch, forcing all chars to be signed

## Compiler flags
if(CMAKE_COMPILER_IS_GNUCXX)
    ## signed char is default on x86 gcc, not on arm however.
    set(CMAKE_CXX_FLAGS "-fsigned-char")        
endif()

Originally posted by philipp.schmutz with karma: 56 on 2015-02-16

This answer was ACCEPTED on the original site

Post score: 4


Original comments

Comment by philipp.schmutz on 2015-02-16:
https://github.com/sbpl/sbpl/pull/27

$\endgroup$
0
$\begingroup$

Rosanswers logo

In general, this error means that SBPL timed out before it could find a path connecting that start and goal points.

There are a few things you can try (in order from easiest to hardest):

  • Make sure SBPL and sbpl_lattice_planner are compiled in release mode ( catkin_make -DCMAKE_BUILD_TYPE=Release )
  • Increase the global planner timeout
  • Decrease the global costmap resolution
  • Decrease the number of SBPL primitives

Originally posted by ahendrix with karma: 47576 on 2014-10-08

This answer was NOT ACCEPTED on the original site

Post score: 1


Original comments

Comment by Markus Eich on 2014-10-09:
This does not seem to help much.

  • compiling with release did not improve the issue
  • Set Global planner time out to 10 seconds. still no result
  • I have set the resolution to 10cm. Still no solution

Decreasing the number of primitives is where I am currently stuck.

Comment by Markus Eich on 2014-10-09:
I am using the genprim_unicylce method. When I set the numberofangles=8, I can generate the primitives but the planner simply crashes.

Comment by ahendrix on 2014-10-09:
You may want to try choosing a goal point that's closer or further away from the robot.

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.