ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

Problem running SBPL on ARM (Odroid-U3)

asked 2014-10-07 09:23:12 -0500

Markus Eich gravatar image

updated 2014-10-08 04:58:46 -0500

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_lattic...

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

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

Cheers,

Markus

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
4

answered 2015-02-16 03:05:16 -0500

philipp.schmutz gravatar image

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...

and here: https://github.com/sbpl/sbpl/blob/mas...

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()
edit flag offensive delete link more

Comments

1

answered 2014-10-08 11:00:50 -0500

ahendrix gravatar image

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
edit flag offensive delete link more

Comments

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.

Markus Eich gravatar image Markus Eich  ( 2014-10-09 10:11:11 -0500 )edit

I am using the genprim_unicylce method. When I set the numberofangles=8, I can generate the primitives but the planner simply crashes.

Markus Eich gravatar image Markus Eich  ( 2014-10-09 10:12:24 -0500 )edit

You may want to try choosing a goal point that's closer or further away from the robot.

ahendrix gravatar image ahendrix  ( 2014-10-09 11:46:10 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2014-10-07 09:23:12 -0500

Seen: 388 times

Last updated: Feb 16 '15