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

Turtlebot bumper

asked 2015-11-24 09:29:53 -0500

MrX gravatar image

updated 2015-11-26 06:56:24 -0500

Hi,

I am setting up a Turtlebot on Indigo. Whenever the robot hits an obstacle it starts shacking (driving forward and backwards quickly). It does not matter whether I am driving with keyop or with a navigation planner. My two most important launch files look like this:

<launch>
  <!-- Run TF setup -->
  <include file = "$(find my_robot)/launch/sensors/tf_transformations.launch" />

  <!-- Run laser node -->
  <include file = "$(find my_robot)/launch/sensors/lasersensor.launch" />

  <!-- Bring up turtlebot -->
  <include file = "$(find turtlebot_bringup)/launch/minimal.launch" />

  <!--- Run AMCL and map_server-->
  <include file = "$(find my_robot)/launch/navigation/amcl.launch" />

  <!-- Run move base framework -->
  <include file = "$(find my_robot)/launch/navigation/move_base.launch" />
</launch>

And the move_base launch file is

<launch>
  <!-- Run smoother and safety controller -->
  <include file="$(find turtlebot_navigation)/launch/includes/velocity_smoother.launch.xml"/>
  <include file="$(find turtlebot_navigation)/launch/includes/safety_controller.launch.xml"/>

  <!-- Run move base framework -->
  <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
    <rosparam file="$(find my_robot)/param/costmap_common_param.yaml" command="load" ns="global_costmap" />
    <rosparam file="$(find my_robot)/param/costmap_common_param.yaml" command="load" ns="local_costmap" />
    <rosparam file="$(find my_robot)/param/local_costmap_param.yaml" command="load" />
    <rosparam file="$(find my_robot)/param/global_costmap_param.yaml" command="load" />
    <rosparam file="$(find my_robot)/param/base_local_planner_param.yaml" command="load" />

    <remap from="cmd_vel" to="navigation_velocity_smoother/raw_cmd_vel"/>
  </node>
</launch>

All velocity outputs are correctly mapped to either

/cmd_vel_mux/input/navi
/cmd_vel_mux/input/safety_controller
/cmd_vel_mux/input/teleop

Assuming that the Turtlebot is brought up, I can push the bumping-detector and it drives back for about 3 cm. If I use teleop and drive it into an obstacle, the safety controller publishes one message on the /cmd_vel_mux/input/safety_controller topic but very shortly after that also a forward velocity is published to /cmd_vel_mux/input/teleop (because thats what I tell it to do). In that case it only reverses 1cm and immediately bumps into the obstacle again.

This is quite bad because if it hits an obstacle once, it will be stuck in this forward-backward shacking movement forever. Can I change this behavior?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2015-11-26 10:25:02 -0500

Chrissi gravatar image

The only thing the mux does is if a message with a higher priority comes in, it blocks all the messages with lower priority. Once that message has been received, it receives all the other messages again which creates exactly the behaviour you described. Looking at the cmd_vel_mux wiki you can defined a timeout after which the topic is considered inactive. Try increasing that for the safety topic.

edit flag offensive delete link more

Comments

Thanks. That solved my problem. I ended up adding the following line (after minimal.launch) to the launch file: <param name="cmd_vel_mux/yaml_cfg_file" value="$(find my_robot)/param/mux.yaml"/>

mux.yaml is the file in which I define my own cmd_vel_mux parameters

MrX gravatar image MrX  ( 2015-11-27 08:06:58 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2015-11-24 09:29:53 -0500

Seen: 1,119 times

Last updated: Nov 26 '15