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

frontier_exploration with turtlebot

asked 2014-10-29 04:35:52 -0500

charkoteow gravatar image

updated 2014-10-30 06:57:57 -0500

I'm trying to get the frontier_exploration package to work with my TurtleBot. But so far it's not working.

The launch file

<launch>
  <node pkg="gmapping" type="slam_gmapping" name="slam_gmapping" output="screen">
    <remap from="scan" to="/scan2" />
    <rosparam>
      occ_thresh: 0.25
      odom_frame: odom
      map_update_interval: 5.0
      maxUrange: 6.0
      maxRange: 8.0
      sigma: 0.05
      kernelSize: 1
      lstep: 0.05
      astep: 0.05
      iterations: 5
      lsigma: 0.075
      ogain: 1.0
      lskip: 0
      srr: 0.01
      srt: 0.02
      str: 0.01
      stt: 0.02
      linearUpdate: 0.5
      angularUpdate: 0.436
      temporalUpdate: -1.0
      resampleThreshold: 0.5
      particles: 80
      xmin: -1.0
      ymin: -1.0
      xmax: 1.0
      ymax: 1.0
      delta: 0.05
      llsamplerange: 0.01
      llsamplestep: 0.01
      lasamplerange: 0.005
      lasamplestep: 0.005
      base_frame: base_link
    </rosparam>
  </node>
  <node name="rviz" pkg="rviz" type="rviz">
  </node>

          <include file="$(find turtlebot_navigation)/launch/includes/velocity_smoother.launch.xml"/>
          <include file="$(find turtlebot_navigation)/launch/includes/safety_controller.launch.xml"/>

          <arg name="odom_topic" default="odom" />

   <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
          <rosparam file="$(find turtlebot_navigation)/param/costmap_common_params.yaml" command="load" ns="global_costmap" />
          <rosparam file="$(find turtlebot_navigation)/param/costmap_common_params.yaml" command="load" ns="local_costmap" />
          <rosparam file="$(find turtlebot_navigation)/param/local_costmap_params.yaml" command="load" />
          <rosparam file="$(find turtlebot_navigation)/param/global_costmap_params.yaml" command="load" />
          <rosparam file="$(find turtlebot_navigation)/param/base_local_planner_params.yaml" command="load" />
          <rosparam file="$(find turtlebot_navigation)/param/move_base_params.yaml" command="load" />
          <remap from="cmd_vel" to="navigation_velocity_smoother/raw_cmd_vel"/>
          <remap from="odom" to="$(arg odom_topic)"/>
</node>
</launch>

global_costmap_params.yaml

global_costmap:
   global_frame: /map
   robot_base_frame: /base_footprint
   update_frequency: 3.0
   publish_frequency: 0.0
   static_map: true
   transform_tolerance: 0.5

local_costmap_params.yaml

local_costmap:
   global_frame: /odom
   robot_base_frame: /base_footprint
   update_frequency: 5.0
   publish_frequency: 2.0
   static_map: false
   rolling_window: true
   width: 4.0
   height: 4.0
   resolution: 0.05
   transform_tolerance: 0.5

Errors from the frontier_exploration terminal

[ WARN] [1414574875.215553173]: Please select an initial point for exploration inside the polygon
[ INFO] [1414574876.981956729]: Sending goal
[ INFO] [1414574877.352866124]: Using plugin "static"
[ INFO] [1414574877.621707478]: Requesting the map...
[ INFO] [1414574877.775594588]: Resizing costmap to 576 X 288 at 0.050000 m/pix
[ INFO] [1414574877.847249155]: Received a 576 X 288 map at 0.050000 m/pix
[ INFO] [1414574877.847298258]: Subscribing to updates
[ INFO] [1414574878.016550480]: Using plugin "explore_boundary"
[ INFO] [1414574878.541237670]: Using plugin "sensor"
[ INFO] [1414574878.664303536]:     Subscribed to Topics: /scan2
[ INFO] [1414574879.327905514]: Using plugin "inflation"
[ERROR] [1414574880.852823897]: Exception thrown while processing service call: Lookup would require extrapolation into the past.  Requested time 1414574873.590463123 but the earliest data is at time 1414574878.157772422, when looking up transform from frame [odom] to frame [map]
[ERROR] [1414574880.853237138]: Service call failed: service [/explore_server/explore_costmap/explore_boundary/update_boundary_polygon] responded with an error: Lookup would require extrapolation into the past.  Requested time 1414574873.590463123 but the earliest data is at time 1414574878.157772422, when looking up transform from frame [odom] to frame [map]
[ERROR] [1414574880.853397382]: Failed to set region boundary

Errors from my gmapping launch file terminal

[ WARN] [1414574406.526808975]: Could not transform the global plan to the frame of the controller ...
(more)
edit retag flag offensive close merge delete

Comments

have you finally got it to work? its driving me nuts lol any luck, progress, idea? here is my Question I'd appreciate any little help. thanks

sobot gravatar image sobot  ( 2015-05-05 14:37:20 -0500 )edit

i really can't pin down the exact problem. sometimes it works, sometimes it doesn't. even with the clock synced properly and i also set the openni publish transform to false to fix the kinect's tf issues. we've moved on from mapping to olfaction recently so I can't help you much for the time being.

charkoteow gravatar image charkoteow  ( 2015-05-06 01:09:27 -0500 )edit

thank you for the response. one last thing, i thought i would borrow the configs that you posted here, to test on my bot. apart from clock n stuff, you did use the same config as posted here right?

sobot gravatar image sobot  ( 2015-05-06 03:57:03 -0500 )edit

Almost all of it are the same. I've increased the transform tolerance, update_frequency, publish_frequency and changed robot_base_frame to base_link on the global costmap params and frontier's launch file. I think they must be the same. Check your launch file....

charkoteow gravatar image charkoteow  ( 2015-05-06 04:32:47 -0500 )edit

...the one i've uploaded was mainly about gmapping & move_base. i think i should update my Q.

charkoteow gravatar image charkoteow  ( 2015-05-06 04:33:35 -0500 )edit

Thanks a bunch for the replies. im so stuck on finding a working exploration package you have no idea lol. have a good day!

sobot gravatar image sobot  ( 2015-05-06 04:47:20 -0500 )edit

Maybe either of you can help me at http://answers.ros.org/question/23700...

130s gravatar image 130s  ( 2016-06-15 00:05:35 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2014-10-29 22:49:24 -0500

paulbovbel gravatar image

updated 2014-10-29 22:58:51 -0500

Due to the time difference in the timestamps (3-5 seconds), it looks like you have tf setup problems, or some serious latency issues.

You can set a tolerance value on amcl to future date the tf timestamps and prevent extrapolation errors, but the most you'd ever need would be ~0.1 s or so.

Are you running the nodes on separate computers? Are the clocks synced with chrony or something similar?

edit flag offensive delete link more

Comments

I am using two computers. One laptop on the bot and a pc as workstation. Ran all the essentials like turtlebot startup and kinect's packages on the laptop. All other nodes are on the pc.

I do get some tf error sometimes. All of it were kinect's tf. It flickers on RViz.

Updated the Q with tf frames

charkoteow gravatar image charkoteow  ( 2014-10-30 06:59:32 -0500 )edit
1

Try going through this

paulbovbel gravatar image paulbovbel  ( 2014-10-30 08:40:23 -0500 )edit
[ WARN] [1417145722.105144612]: Could not get robot pose, cancelling reconfiguration
charkoteow gravatar image charkoteow  ( 2014-11-27 21:39:33 -0500 )edit

That is also a TF issue, likely cause by your multi-machine setup. Please open a separate question if you need more info about setting up your network properly. Main issues would be latency, and time synchronization.

paulbovbel gravatar image paulbovbel  ( 2014-11-28 10:08:57 -0500 )edit

Hi, I am having the exact same problem as described in this post but I'm not running on multiple workstations. I am running everything on one computer and i'm running the nodes separately by their own launch file (i.e. gmapping, move_base, TF from odom->base_link->laser, and exploration).

RND gravatar image RND  ( 2015-03-10 04:41:36 -0500 )edit

Also, I'm using gmapping to provide the map->odom transform and of course to build the map.

RND gravatar image RND  ( 2015-03-10 05:02:28 -0500 )edit

I doubt it's the exact same problem, since @charkoteow's issue was extremely post-dated timestamps. Either way, please open a new question, and provide some more information.

paulbovbel gravatar image paulbovbel  ( 2015-03-10 08:31:34 -0500 )edit

Question Tools

Stats

Asked: 2014-10-29 04:35:52 -0500

Seen: 1,644 times

Last updated: Oct 30 '14