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

Challenges with headless turtlebot_gazebo on remote machine [closed]

asked 2012-03-10 05:41:37 -0500

SL Remy gravatar image

Before trying this I did update my ubuntu/ROS machine. Using ros-electric-simulator-gazebo-1.4.12 and trying to run simulated turtlebot headless (i.e. with no OGRE rendering via the -r argument).

[..../simulator_gazebo/gazebo/build/gazebo/server/sensors/Sensor.cc:175] left_cliff_sensor sensor has no controller.

Duplicated for leftfront_cliff_sensor, right_cliff_sensor, rightfront_cliff_sensor, and wall_sensor.

How do I fix this? Is this some how related to the lack of OGRE rendering somehow?

Also, occasionally I observe the following message (repeatedly) when I run the roslaunch command (I make no changes between tries).

[ERROR] [1331395233.928128897, 0.915000000]: TF_NAN_INPUT: Ignoring transform for child_frame_id "/wheelodom" from authority "default_authority" because of a nan value in the transform (nan nan nan) (0.000000 0.000000 0.764947 0.644094)

What should I do to track that down?

Finally, sometimes the /odom isn't what I'd expect it to be as well.

pose: 
  pose: 
    position: 
      x: 6.97715623635e+22
      y: 1.83193543179e+25

and other times it is:

pose: 
  pose: 
    position: 
      x: -1.70336659266e-06
      y: -7.78686316816e-12

In this latter case the system responds to twist commands as would be expected.

I assume that the simulation has "exploded" in the former case as the robot doesn't move when twist commands are issued (at least according to /odom).

edit retag flag offensive reopen merge delete

Closed for the following reason the question is answered, right answer was accepted by SL Remy
close date 2013-01-30 11:22:18

1 Answer

Sort by ยป oldest newest most voted
1

answered 2012-03-11 04:27:00 -0500

keizo gravatar image

Hi. I hope this information helps you.

The problem you see may be the same problem that I found last week.

I found "using variables without initialize" bug in "simulator_gazebo_plugins". That cause the very large value of odometry {x, y}.

[problem] When you try to use turtlebot simulator (gazebo), sometimes the node "/gazebo" publishes the topic "/odom" with very large initial position {x, y} like 1e+31 or so.

[cause] In turtlebot_gazebo_plugins/src/gazebo_ros_create.cpp, variables below are used without being initialized.

  • prev_update_time
  • odom_pose[0]
  • odom_pose[1]
  • odom_pose[2]

I know that recentry turtlebot_gazebo_plugins/src/gazebo_ros_create.cpp was patched about NaN value (in GazeboRosCreate::UpdateChild()) . The patch didn't fix the problem I found.

I don't know how to report bug-report and patch, so I'm glad if someone does.

[environment]

  • ubuntu 11.10 32bit
  • ros-electric (updated with apt-get)

[how to reproduce] (not 100%. because that is caused with "using uninitialized variable" in C++.)

Start 3 terminals separately and type it.

$ roscore
$ roslaunch turtlebot_gazebo turtlebot_empty_world.launch
$ rostopic echo /odom

Check values of pose.pose.position.x and y. If it shows like below, you successed to reproduce.

pose:
  pose:
    position:
      x: 1.86493744726e+31
      y: 4.86171422416e+30

[how to fix] initialize variables.

[patch] keizo@soi:~/ros_workspace/turtlebot_gazebo_plugins.keizo/src$ diff -c /opt/ros/electric/stacks /turtlebot_simulator/turtlebot_gazebo_plugins/src/gazebo_ros_create.cpp .

*** /opt/ros/electric/stacks/turtlebot_simulator/turtlebot_gazebo_plugins/src/gazebo_ros_create.cpp 2012-02-29 07:52:33.000000000 +0900
--- ./gazebo_ros_create.cpp 2012-03-11 22:59:59.026536682 +0900
***************
*** 153,158 ****
--- 153,159 ----
    js_.velocity.push_back(0);
    js_.effort.push_back(0);

+   prev_update_time_ = 0;
    last_cmd_vel_time_ = 0;
  }

***************
*** 172,177 ****
--- 173,184 ----
    if (joints_[FRONT]) set_joints_[FRONT] = true;
    if (joints_[REAR]) set_joints_[REAR] = true;

+   //initialize time and odometry position
+   prev_update_time_ = last_cmd_vel_time_ =
+     Simulator::Instance()->GetSimTime();
+   odom_pose_[0] = 0.0;
+   odom_pose_[1] = 0.0;
+   odom_pose_[2] = 0.0;
  }

  void GazeboRosCreate::FiniChild()

[[[ Unnecessary additional information ]]] [indirect problem] When you try to use turtlebot simulator (gazebo) and slam_gmapping, the node slam_gmapping downs with a message "bad_alloc" exception.

[cause] Ordinary, the initial value of odometory's {x, y} should be nearly equal to zero. but it shows sometimes very large like 1e+31 or so.

When the node "slam_gmapping" receives that large value, it try to enlarge map too much. And it cause a "not enough memory" situation and "bad_alloc" exception.

If you want to reproduce, you need to add "output_frame" param described blelow to turtlebot_gazebo/launch/robot.launch .

 <node pkg="robot_pose_ekf parameter" .... >
    ....
    <param name="output_frame" value="odom"/>
 </node>

[comment] I'm not good at English, I apologize about my poor English. I hope this information helps you. and also me.

edit flag offensive delete link more

Question Tools

Stats

Asked: 2012-03-10 05:41:37 -0500

Seen: 551 times

Last updated: Mar 11 '12