TurtleBot3

turtlebot3_dimension1

turtlebot3_burger_components

ROS软件包:

  • turtlebot3_bringup
  • turtlebot3_description
  • turtlebot3_example
  • turtlebot3_teleop
  • turtlebot3_slam
  • turtlebot3_navigation

建图与导航时的所有坐标系:

frames

建图时运行节点与相关话题:

rosgraph_slam

导航时运行节点与相关话题:

rosgraph_nav

URDF

link和joint

常用命令

notes

roscore
[RPi]roslaunch turtlebot3_bringup turtlebot3_robot.launch

[显示]roslaunch turtlebot3_bringup turtlebot3_model.launch
[手柄]roslaunch teleop_twist_joy teleop.launch
[建图]roslaunch turtlebot3_slam turtlebot3_slam.launch
[存图]rosrun map_server map_saver -f ~/map
[导航]roslaunch turtlebot3_navigation turtlebot3_navigation.launch map_file:=$HOME/map.yaml

航迹推演(注:yaw默认用IMU数据)

/*******************************************************************************
* Calculate the odometry
*******************************************************************************/
bool calcOdometry(double diff_time)
{
  float* orientation;
  double wheel_l, wheel_r;      // rotation value of wheel [rad]
  double delta_s, theta, delta_theta;
  static double last_theta = 0.0;
  double v, w;                  // v = translational velocity [m/s], w = rotational velocity [rad/s]
  double step_time;

  wheel_l = wheel_r = 0.0;
  delta_s = delta_theta = theta = 0.0;
  v = w = 0.0;
  step_time = 0.0;

  step_time = diff_time;

  if (step_time == 0)
    return false;

  wheel_l = TICK2RAD * (double)last_diff_tick[LEFT];
  wheel_r = TICK2RAD * (double)last_diff_tick[RIGHT];

  if (isnan(wheel_l))
    wheel_l = 0.0;

  if (isnan(wheel_r))
    wheel_r = 0.0;

  delta_s     = WHEEL_RADIUS * (wheel_r + wheel_l) / 2.0;
  // theta = WHEEL_RADIUS * (wheel_r - wheel_l) / WHEEL_SEPARATION;
  orientation = sensors.getOrientation();
  theta       = atan2f(orientation[1]*orientation[2] + orientation[0]*orientation[3],
                0.5f - orientation[2]*orientation[2] - orientation[3]*orientation[3]);

  delta_theta = theta - last_theta;

  // compute odometric pose
  odom_pose[0] += delta_s * cos(odom_pose[2] + (delta_theta / 2.0));
  odom_pose[1] += delta_s * sin(odom_pose[2] + (delta_theta / 2.0));
  odom_pose[2] += delta_theta;

  // compute odometric instantaneouse velocity

  v = delta_s / step_time;
  w = delta_theta / step_time;

  odom_vel[0] = v;
  odom_vel[1] = 0.0;
  odom_vel[2] = w;

  last_velocity[LEFT]  = wheel_l / step_time;
  last_velocity[RIGHT] = wheel_r / step_time;
  last_theta = theta;

  return true;
}

参考文献