Browse Source

新增小车校准软件包

corvin 5 years ago
parent
commit
733608d79b

+ 198 - 0
src/robot_calibration/CMakeLists.txt

@@ -0,0 +1,198 @@
+cmake_minimum_required(VERSION 2.8.3)
+project(robot_calibration)
+
+## Compile as C++11, supported in ROS Kinetic and newer
+# add_compile_options(-std=c++11)
+
+## Find catkin macros and libraries
+## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
+## is used, also find other catkin packages
+find_package(catkin REQUIRED COMPONENTS
+  rospy
+  std_msgs
+)
+
+## System dependencies are found with CMake's conventions
+# find_package(Boost REQUIRED COMPONENTS system)
+
+
+## Uncomment this if the package has a setup.py. This macro ensures
+## modules and global scripts declared therein get installed
+## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
+# catkin_python_setup()
+
+################################################
+## Declare ROS messages, services and actions ##
+################################################
+
+## To declare and build messages, services or actions from within this
+## package, follow these steps:
+## * Let MSG_DEP_SET be the set of packages whose message types you use in
+##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
+## * In the file package.xml:
+##   * add a build_depend tag for "message_generation"
+##   * add a build_depend and a run_depend tag for each package in MSG_DEP_SET
+##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in
+##     but can be declared for certainty nonetheless:
+##     * add a run_depend tag for "message_runtime"
+## * In this file (CMakeLists.txt):
+##   * add "message_generation" and every package in MSG_DEP_SET to
+##     find_package(catkin REQUIRED COMPONENTS ...)
+##   * add "message_runtime" and every package in MSG_DEP_SET to
+##     catkin_package(CATKIN_DEPENDS ...)
+##   * uncomment the add_*_files sections below as needed
+##     and list every .msg/.srv/.action file to be processed
+##   * uncomment the generate_messages entry below
+##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
+
+## Generate messages in the 'msg' folder
+# add_message_files(
+#   FILES
+#   Message1.msg
+#   Message2.msg
+# )
+
+## Generate services in the 'srv' folder
+# add_service_files(
+#   FILES
+#   Service1.srv
+#   Service2.srv
+# )
+
+## Generate actions in the 'action' folder
+# add_action_files(
+#   FILES
+#   Action1.action
+#   Action2.action
+# )
+
+## Generate added messages and services with any dependencies listed here
+# generate_messages(
+#   DEPENDENCIES
+#   std_msgs
+# )
+
+################################################
+## Declare ROS dynamic reconfigure parameters ##
+################################################
+
+## To declare and build dynamic reconfigure parameters within this
+## package, follow these steps:
+## * In the file package.xml:
+##   * add a build_depend and a run_depend tag for "dynamic_reconfigure"
+## * In this file (CMakeLists.txt):
+##   * add "dynamic_reconfigure" to
+##     find_package(catkin REQUIRED COMPONENTS ...)
+##   * uncomment the "generate_dynamic_reconfigure_options" section below
+##     and list every .cfg file to be processed
+
+## Generate dynamic reconfigure parameters in the 'cfg' folder
+# generate_dynamic_reconfigure_options(
+#   cfg/DynReconf1.cfg
+#   cfg/DynReconf2.cfg
+# )
+
+###################################
+## catkin specific configuration ##
+###################################
+## The catkin_package macro generates cmake config files for your package
+## Declare things to be passed to dependent projects
+## INCLUDE_DIRS: uncomment this if your package contains header files
+## LIBRARIES: libraries you create in this project that dependent projects also need
+## CATKIN_DEPENDS: catkin_packages dependent projects also need
+## DEPENDS: system dependencies of this project that dependent projects also need
+catkin_package(
+#  INCLUDE_DIRS include
+#  LIBRARIES carebot_calibration
+#  CATKIN_DEPENDS roscpp rospy std_msgs
+#  DEPENDS system_lib
+)
+
+###########
+## Build ##
+###########
+
+## Specify additional locations of header files
+## Your package locations should be listed before other locations
+include_directories(
+# include
+  ${catkin_INCLUDE_DIRS}
+)
+
+## Declare a C++ library
+# add_library(${PROJECT_NAME}
+#   src/${PROJECT_NAME}/carebot_calibration.cpp
+# )
+
+## Add cmake target dependencies of the library
+## as an example, code may need to be generated before libraries
+## either from message generation or dynamic reconfigure
+# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
+
+## Declare a C++ executable
+## With catkin_make all packages are built within a single CMake context
+## The recommended prefix ensures that target names across packages don't collide
+# add_executable(${PROJECT_NAME}_node src/carebot_calibration_node.cpp)
+
+## Rename C++ executable without prefix
+## The above recommended prefix causes long target names, the following renames the
+## target back to the shorter version for ease of user use
+## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
+# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
+
+## Add cmake target dependencies of the executable
+## same as for the library above
+# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
+
+## Specify libraries to link a library or executable target against
+# target_link_libraries(${PROJECT_NAME}_node
+#   ${catkin_LIBRARIES}
+# )
+
+#############
+## Install ##
+#############
+
+# all install targets should use catkin DESTINATION variables
+# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
+
+## Mark executable scripts (Python etc.) for installation
+## in contrast to setup.py, you can choose the destination
+# install(PROGRAMS
+#   scripts/my_python_script
+#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
+# )
+
+## Mark executables and/or libraries for installation
+# install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node
+#   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
+#   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
+#   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
+# )
+
+## Mark cpp header files for installation
+# install(DIRECTORY include/${PROJECT_NAME}/
+#   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
+#   FILES_MATCHING PATTERN "*.h"
+#   PATTERN ".svn" EXCLUDE
+# )
+
+## Mark other files for installation (e.g. launch and bag files, etc.)
+# install(FILES
+#   # myfile1
+#   # myfile2
+#   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
+# )
+
+#############
+## Testing ##
+#############
+
+## Add gtest based cpp test target and link libraries
+# catkin_add_gtest(${PROJECT_NAME}-test test/test_carebot_calibration.cpp)
+# if(TARGET ${PROJECT_NAME}-test)
+#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
+# endif()
+
+## Add folders to be run by python nosetests
+# catkin_add_nosetests(test)

+ 34 - 0
src/robot_calibration/config/angular_calibrate_params.yaml

@@ -0,0 +1,34 @@
+#######################################################################
+# Copyright: 2016-2018(c) ROS小课堂 www.corvin.cn
+#######################################################################
+# Author: corvin
+#######################################################################
+# Description:
+#  该参数文件是为校准小车的角速度而设置,大家可以根据需要酌情来修改各
+#  个参数,各参数功能介绍分别是:
+#  test_circle:测试小车需要转动的圈数,默认2,正转2圈。
+#  angular_speed:小车转动时的角速度多大,default 0.2rad/s。
+#  tolerance_angle:在测试转动时可以容忍的误差,默认0.05弧度。
+#  angular_scale:校准小车在转动时的精度,根据小车实际转动的角度除以规定
+#    的角度得到结果作为新的angular_scale值,再一次运行,根据这次的误差
+#    乘以angular_scale作为这次的新angular_scale,一直测试直到最终实际
+#    角度达到预期。
+#  check_odom_rate:while循环查询转动角度的频率.
+#  cmd_topic:控制小车移动的话题.
+#  base_frame:小车的基坐标系。
+#  odom_frame:小车里程计的坐标系。
+#######################################################################
+# History:
+#  20180111:初始化该参数文件。
+#  20180206:增加angular_scale配置参数。
+#  20180425:将test_angle测试角度改为test_circle,直接指定测试几圈,
+#      将角速度从0.5rad/s改为0.2rad/s,tolerance_angel从0.03->0.05.
+#######################################################################
+test_circle: 2 #test run circle
+angular_speed: 0.2  #default 0.2rad/s
+tolerance_angle: 0.04 #tolerance radians
+angular_scale: 1.00
+check_odom_rate: 15 #check odom rate
+cmd_topic: /cmd_vel
+base_frame: base_footprint
+odom_frame: odom

+ 35 - 0
src/robot_calibration/config/linear_calibrate_params.yaml

@@ -0,0 +1,35 @@
+#######################################################################
+# Copyright: 2016-2018 ROS小课堂 www.corvin.cn
+#######################################################################
+# Author: corvin
+#######################################################################
+# Description:
+#  该参数文件是为校准小车的线速度而设置,大家可以根据需要酌情来修改各
+#  个参数,各参数功能介绍分别是:
+#  test_distance:测试小车需要移动的距离,默认是2米。
+#  linear_speed:小车移动时速度多大。
+#  tolerance_linear:在测试移动时可以容忍的误差。
+#  linear_scale:小车在移动中线速度精度,根据小车实际走的距离去除以
+#    test_distance得到的数据就是,如果小车走的还是不准确的话就继续
+#    运行一次,根据实际走的距离乘以当前的linear_scale作为新的linear_scale.
+#  check_rate:根据小车底盘发布里程计坐标的频率来设置检查的频率.
+#  cmd_topic:小车底盘订阅控制其移动的话题名称.
+#  base_frame:小车底盘的基坐标系.
+#  odom_frame:小车里程计的坐标系,我们需要查询这两个坐标系之间的距离来
+#    判断我们的小车是否移动到了指定的距离.
+#  我们最终标定完以后,只需要记下这个linear_scale参数就可以了.我们需要将
+#  该参数配置在控制我们小车底盘移动的上位机代码中.这样我们的小车以后在
+#  移动时距离精度就会很好了.
+#######################################################################
+# History:
+#  20180111:初始化该参数文件.
+#  20180911:增加check_rate和cmd_topic两个参数.
+#######################################################################
+test_distance: 2.0  # m
+linear_speed: 0.17  # m/s
+tolerance_linear: 0.005  # 0.5cm
+linear_scale: 1.0
+check_rate: 16
+cmd_topic: /cmd_vel
+base_frame: base_footprint
+odom_frame: odom

+ 173 - 0
src/robot_calibration/config/rviz_config.rviz

@@ -0,0 +1,173 @@
+Panels:
+  - Class: rviz/Displays
+    Help Height: 0
+    Name: Displays
+    Property Tree Widget:
+      Expanded:
+        - /TF1/Frames1
+      Splitter Ratio: 0.459227
+    Tree Height: 437
+  - Class: rviz/Selection
+    Name: Selection
+  - Class: rviz/Tool Properties
+    Expanded:
+      - /2D Pose Estimate1
+      - /2D Nav Goal1
+      - /Publish Point1
+    Name: Tool Properties
+    Splitter Ratio: 0.588679
+  - Class: rviz/Views
+    Expanded:
+      - /Current View1
+    Name: Views
+    Splitter Ratio: 0.5
+  - Class: rviz/Time
+    Experimental: false
+    Name: Time
+    SyncMode: 0
+    SyncSource: ""
+Visualization Manager:
+  Class: ""
+  Displays:
+    - Alpha: 0.2
+      Cell Size: 1
+      Class: rviz/Grid
+      Color: 191; 220; 182
+      Enabled: true
+      Line Style:
+        Line Width: 0.03
+        Value: Lines
+      Name: Grid
+      Normal Cell Count: 0
+      Offset:
+        X: 8
+        Y: 8
+        Z: 0
+      Plane: XY
+      Plane Cell Count: 30
+      Reference Frame: <Fixed Frame>
+      Value: true
+    - Alpha: 0.3
+      Class: rviz/RobotModel
+      Collision Enabled: false
+      Enabled: true
+      Links:
+        All Links Enabled: true
+        Expand Joint Details: false
+        Expand Link Details: false
+        Expand Tree: false
+        Link Tree Style: Links in Alphabetic Order
+        base_footprint:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        base_imu_link:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        base_link:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        laser:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+      Name: RobotModel
+      Robot Description: robot_description
+      TF Prefix: ""
+      Update Interval: 0
+      Value: true
+      Visual Enabled: true
+    - Class: rviz/TF
+      Enabled: true
+      Frame Timeout: 15
+      Frames:
+        All Enabled: false
+        base_footprint:
+          Value: true
+        base_imu_link:
+          Value: false
+        base_link:
+          Value: false
+        laser:
+          Value: false
+        odom:
+          Value: true
+      Marker Scale: 0.5
+      Name: TF
+      Show Arrows: true
+      Show Axes: true
+      Show Names: true
+      Tree:
+        odom:
+          base_footprint:
+            base_link:
+              base_imu_link:
+                laser:
+                  {}
+      Update Interval: 0
+      Value: true
+  Enabled: true
+  Global Options:
+    Background Color: 48; 48; 48
+    Fixed Frame: odom
+    Frame Rate: 30
+  Name: root
+  Tools:
+    - Class: rviz/Interact
+      Hide Inactive Objects: true
+    - Class: rviz/MoveCamera
+    - Class: rviz/Select
+    - Class: rviz/FocusCamera
+    - Class: rviz/Measure
+    - Class: rviz/SetInitialPose
+      Topic: /initialpose
+    - Class: rviz/SetGoal
+      Topic: /move_base_simple/goal
+    - Class: rviz/PublishPoint
+      Single click: true
+      Topic: /clicked_point
+  Value: true
+  Views:
+    Current:
+      Class: rviz/Orbit
+      Distance: 2.43991
+      Enable Stereo Rendering:
+        Stereo Eye Separation: 0.06
+        Stereo Focal Distance: 1
+        Swap Stereo Eyes: false
+        Value: false
+      Focal Point:
+        X: 1.16892
+        Y: 0.333107
+        Z: -0.00418486
+      Name: Current View
+      Near Clip Distance: 0.01
+      Pitch: 0.674798
+      Target Frame: <Fixed Frame>
+      Value: Orbit (rviz)
+      Yaw: 4.72363
+    Saved: ~
+Window Geometry:
+  Displays:
+    collapsed: true
+  Height: 998
+  Hide Left Dock: true
+  Hide Right Dock: true
+  QMainWindow State: 000000ff00000000fd00000004000000000000016a0000035ffc020000000bfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006400fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df0000018500000127fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007300000000280000035f000000dd00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e006701000001ad000001d70000000000000000fb0000000c00430061006d006500720061010000036e000000160000000000000000fb0000000a0049006d00610067006501000001c4000001c30000000000000000000000010000010f0000035cfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0056006900650077007300000000280000035c000000b000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000006900000003bfc0100000002fb0000000800540069006d0065010000000000000690000002f600fffffffb0000000800540069006d00650100000000000004500000000000000000000006900000035f00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
+  Selection:
+    collapsed: false
+  Time:
+    collapsed: false
+  Tool Properties:
+    collapsed: false
+  Views:
+    collapsed: true
+  Width: 1680
+  X: 53
+  Y: 14

+ 21 - 0
src/robot_calibration/launch/calibrate_mobilebase_angular.launch

@@ -0,0 +1,21 @@
+<!--
+  Copyright(C): 2016-2018 ROS小课堂 www.corvin.cn
+  Author: corvin
+  Description:
+    进行小车底盘角速度标定的launch启动文件,首先启动小车的urdf描述启动文件,用于在
+    rviz中进行查看标定过程.然后启动控制底盘移动的launch文件,最后启动角速度标定的
+    python脚本,并且启动时要加载相应配置参数.
+  History:
+    20180425: init this file.
+-->
+<launch>
+  <!--startup robot urdf description file-->
+  <include file="$(find robot_description)/launch/robot_description.launch" />
+
+  <!--startup mobilebase arduino launch -->
+  <include file="$(find ros_arduino_python)/launch/arduino.launch" />
+
+  <node pkg="robot_calibration" type="calibrate_mobilebase_angular.py" name="calibrate_angular_node" output="screen" >
+    <rosparam file="$(find robot_calibration)/config/angular_calibrate_params.yaml" command="load" />
+  </node>
+</launch>

+ 28 - 0
src/robot_calibration/launch/calibrate_mobilebase_linear.launch

@@ -0,0 +1,28 @@
+<!--
+ Copyright: 2016-2018 ROS小课堂 www.corvin.cn
+ Author: corvin
+ Description:该launch文件是用于对三轮全向移动小车底盘的线速度进行标定.通过设置往前移动的
+   指定距离,然后实地测量小车底盘的实际移动距离与设定的移动距离的误差.根据该误差修正配置
+   参数,从而可以减小该误差,使小车底盘移动距离更准确,为后面的自动导航做好准备工作.
+   该启动文件主要启动流程如下:
+   1.启动小车的urdf文件,这样方便在RViz中查看整个标定过程.
+   2.启动小车控制底盘移动的上位机程序.
+   3.启动标定程序,从配置文件中读取测试移动距离、移动速度、控制移动的话题等配置信息.
+     根据该信息来控制小车移动,测试完成后,需要拿出米尺来测量小车的实际移动距离与配置
+     的移动距离的差值,然后标定程序会根据测量值来修正配置参数,直到实际的移动距离与配
+     置的移动距离之间的误差在可容忍范围内即可.最后的linear_scale参数就是最终的标定参数,
+     到这里线速度标定过程完毕,最后我们将linear_scale写入到控制小车移动的上位机配置文件中即可.
+ History:
+   20180907:initial this comment.
+-->
+<launch>
+    <!--startup robot urdf description -->
+    <include file="$(find robot_description)/launch/robot_description.launch"/>
+
+    <!--startup mobilebase arduino launch -->
+    <include file="$(find ros_arduino_python)/launch/arduino.launch" />
+
+    <node pkg="robot_calibration" type="calibrate_mobilebase_linear.py" name="calibrate_mobilebase_linear" output="screen">
+        <rosparam file="$(find robot_calibration)/config/linear_calibrate_params.yaml" command="load" />
+    </node>
+</launch>

+ 11 - 0
src/robot_calibration/launch/rviz_display.launch

@@ -0,0 +1,11 @@
+<!--
+  Copyright: 2016-2018 ROS小课堂 www.corvin.cn
+  Author: corvin
+  Description:可以在小车的线速度和角速度标定过程中,在rviz中查看整个过程.
+  History:
+    20180915: initial this file.
+-->
+<launch>
+  <!-- startup rviz with config file -->
+  <node name="rviz" type="rviz" pkg="rviz" args="-d $(find carebot_calibration)/config/rviz_config.rviz" />
+</launch>

+ 65 - 0
src/robot_calibration/package.xml

@@ -0,0 +1,65 @@
+<?xml version="1.0"?>
+<package format="2">
+  <name>robot_calibration</name>
+  <version>0.0.0</version>
+  <description>The robot_calibration package</description>
+
+  <!-- One maintainer tag required, multiple allowed, one person per tag -->
+  <!-- Example:  -->
+  <!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
+  <maintainer email="corvin@todo.todo">corvin</maintainer>
+
+
+  <!-- One license tag required, multiple allowed, one license per tag -->
+  <!-- Commonly used license strings: -->
+  <!--   BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
+  <license>TODO</license>
+
+
+  <!-- Url tags are optional, but multiple are allowed, one per tag -->
+  <!-- Optional attribute type can be: website, bugtracker, or repository -->
+  <!-- Example: -->
+  <!-- <url type="website">http://wiki.ros.org/carebot_calibration</url> -->
+
+
+  <!-- Author tags are optional, multiple are allowed, one per tag -->
+  <!-- Authors do not have to be maintainers, but could be -->
+  <!-- Example: -->
+  <!-- <author email="jane.doe@example.com">Jane Doe</author> -->
+
+
+  <!-- The *depend tags are used to specify dependencies -->
+  <!-- Dependencies can be catkin packages or system dependencies -->
+  <!-- Examples: -->
+  <!-- Use depend as a shortcut for packages that are both build and exec dependencies -->
+  <!--   <depend>roscpp</depend> -->
+  <!--   Note that this is equivalent to the following: -->
+  <!--   <build_depend>roscpp</build_depend> -->
+  <!--   <exec_depend>roscpp</exec_depend> -->
+  <!-- Use build_depend for packages you need at compile time: -->
+  <!--   <build_depend>message_generation</build_depend> -->
+  <!-- Use build_export_depend for packages you need in order to build against this package: -->
+  <!--   <build_export_depend>message_generation</build_export_depend> -->
+  <!-- Use buildtool_depend for build tool packages: -->
+  <!--   <buildtool_depend>catkin</buildtool_depend> -->
+  <!-- Use exec_depend for packages you need at runtime: -->
+  <!--   <exec_depend>message_runtime</exec_depend> -->
+  <!-- Use test_depend for packages you need only for testing: -->
+  <!--   <test_depend>gtest</test_depend> -->
+  <!-- Use doc_depend for packages you need only for building documentation: -->
+  <!--   <doc_depend>doxygen</doc_depend> -->
+  <buildtool_depend>catkin</buildtool_depend>
+  <build_depend>rospy</build_depend>
+  <build_depend>std_msgs</build_depend>
+  <build_export_depend>rospy</build_export_depend>
+  <build_export_depend>std_msgs</build_export_depend>
+  <exec_depend>rospy</exec_depend>
+  <exec_depend>std_msgs</exec_depend>
+
+
+  <!-- The export tag contains other, unspecified, tags -->
+  <export>
+    <!-- Other tools can request additional information be placed here -->
+
+  </export>
+</package>

+ 142 - 0
src/robot_calibration/src/calibrate_mobilebase_angular.py

@@ -0,0 +1,142 @@
+#!/usr/bin/env python
+# _*_ coding:utf-8 _*_
+
+"""
+  Copyright(c):2016-2019 ROS小课堂 www.corvin.cn
+  Author: corvin
+  Description:
+    三轮全向移动小车底盘角速度标定的源码文件.
+  History:
+    20180425: init this file.
+    20180919:增加结束时自动计算angular_scale的功能.
+"""
+import tf
+import PyKDL
+import rospy
+from math import radians, pi
+from nav_msgs.msg import Odometry
+from geometry_msgs.msg import Twist, Quaternion
+
+
+class CalibrateAngular():
+    def __init__(self):
+        rospy.init_node('calibrate_angular_node', anonymous=False)
+        rospy.on_shutdown(self.shutdown)
+
+        #from config file get param
+        self.get_param()
+
+        # How fast will we check the odometry values?
+        check_rate = rospy.Rate(self.rate)
+
+        # Initialize the tf listener
+        self.tf_listener = tf.TransformListener()
+        rospy.sleep(2)
+
+        # Make sure we see the odom and base frames
+        self.tf_listener.waitForTransform(self.odom_frame, self.base_frame, rospy.Time(), rospy.Duration(10.0))
+
+        #initial parameters
+        self.init_param()
+        self.last_angle = 0
+
+        # config move cmd msg
+        move_cmd = Twist()
+        move_cmd.angular.z = self.speed
+
+        while not rospy.is_shutdown():
+            if self.rest_angle > self.tolerance:
+                # Get the current rotation angle from tf
+                odom_angle = self.get_odom_angle()
+                rospy.loginfo("current rotation angle: " + str(odom_angle))
+
+                # Compute how far we have gone since the last measurement
+                delta_angle = self.angular_scale*self.normalize_angle(odom_angle - self.last_angle)
+                self.turn_angle += abs(delta_angle)
+
+                # Compute the rest angle
+                self.rest_angle = self.test_angle - self.turn_angle
+                rospy.loginfo("-->rest_angle: " + str(self.rest_angle))
+
+                # Store the current angle for the next comparison
+                self.last_angle = odom_angle
+
+                self.cmd_vel.publish(move_cmd)
+                check_rate.sleep()
+            else: #end test
+                self.print_result()
+
+    def get_param(self):
+        try:
+            self.rate = rospy.get_param("~check_odom_rate", 15)
+            self.circle_cnt = rospy.get_param("~test_circle", 2)
+            self.test_angle = eval('self.circle_cnt*2*pi')
+
+            self.speed = rospy.get_param("~angular_speed", 0.2) #radians speed
+            self.tolerance = rospy.get_param("~tolerance_angle", 0.05)
+            self.angular_scale = rospy.get_param("~angular_scale", 1.00)
+
+            cmd_topic = rospy.get_param("~cmd_topic", '/cmd_vel')
+            self.cmd_vel = rospy.Publisher(cmd_topic, Twist, queue_size=10)
+
+            # Get base frame and odom frame
+            self.base_frame = rospy.get_param('~base_frame', '/base_footprint')
+            self.odom_frame = rospy.get_param('~odom_frame', '/odom')
+        except:
+            rospy.logerr("ERROR: Get config param error from yaml file...")
+
+    def init_param(self):
+        self.start_time = rospy.get_time()
+        self.rest_angle = self.test_angle
+        self.turn_angle = 0.0
+
+    def print_result(self):
+        end_time = rospy.get_time() #get test end time
+        rospy.logwarn("---------------------------------")
+        rospy.logwarn("---Angular Calibrate Completed---")
+        rospy.logwarn("---------------------------------")
+        rospy.logwarn("Test angle:" + str(self.test_angle))
+        rospy.logwarn("Test Time:"  + str(end_time-self.start_time))
+        rospy.logwarn("Test Speed:" + str(self.test_angle/(end_time-self.start_time)))
+        rospy.logwarn("Input Speed:" + str(self.speed))
+        rospy.logwarn("Angular Scale:" + str(self.angular_scale))
+        actual_degree = input("Please input actual turn degree:")
+        angular_scale = float(radians(actual_degree)/self.test_angle)
+        self.angular_scale *= angular_scale
+        rospy.logwarn("Now get new angular_scale:" + str(self.angular_scale))
+        self.init_param()
+
+    def normalize_angle(self, angle):
+        res = angle
+        while res > pi:
+            res -= 2.0*pi
+        while res < -pi:
+            res += 2.0*pi
+        return res
+
+    def quat_to_angle(self, quat):
+        rot = PyKDL.Rotation.Quaternion(quat.x, quat.y, quat.z, quat.w)
+        return rot.GetRPY()[2]
+
+    # Get the current transform between the odom and base frames
+    def get_odom_angle(self):
+        try:
+            (position, quat) = self.tf_listener.lookupTransform(self.odom_frame, self.base_frame, rospy.Time(0))
+        except (tf.Exception, tf.ConnectivityException, tf.LookupException):
+            rospy.logerr("get_odom_angle: TF Exception !")
+            return
+        # Convert the rotation from a quaternion to an Euler angle
+        return self.quat_to_angle(Quaternion(*quat))
+
+    def shutdown(self):
+        rospy.logwarn("shutdown():Stopping the robot...")
+        self.cmd_vel.publish(Twist())
+        rospy.sleep(1)
+
+if __name__ == '__main__':
+    try:
+        CalibrateAngular()
+        rospy.spin()
+    except:
+        rospy.logerr("Error: Calibration terminated.")
+

+ 125 - 0
src/robot_calibration/src/calibrate_mobilebase_linear.py

@@ -0,0 +1,125 @@
+#!/usr/bin/env python
+# -*- coding: UTF-8 -*-
+
+"""
+ Copyright: 2016-2018 ROS小课堂 www.corvin.cn
+ Author: corvin
+ Description:
+  该源码文件是标定三轮全向移动小车的底盘线速度的代码,标定的主要过程
+  就是根据设定的移动距离,然后向小车的移动话题中发布移动速度.在此时,
+  不断的监听小车自身的基坐标系与odom坐标系之间的距离.当检测到两坐标
+  系之间的距离已经小于容忍范围内,说明小车已经到了指定的移动距离.
+  此时就需要测量小车的实际移动距离跟坐标系间检测的距离是否一样,
+  两者之间的误差是否可以接受,如果不接受就需要修改里程计的修正值.
+ History:
+  20180907: initial this file.
+"""
+import tf
+import rospy
+from math import copysign, sqrt, pow
+from geometry_msgs.msg import Twist, Point
+
+class CalibrateLinear():
+    def __init__(self):
+        rospy.init_node('calibrate_linear_node', anonymous=False)
+
+        #execute a shutdown function when terminating the script
+        rospy.on_shutdown(self.shutdown)
+
+        self.test_distance = rospy.get_param("~test_distance", 2.0)
+        self.speed     = rospy.get_param("~linear_speed", 0.17)
+        self.tolerance = rospy.get_param("~tolerance_linear", 0.005)
+        self.odom_linear_scale = rospy.get_param("~linear_scale", 1.000)
+        self.rate  = rospy.get_param("~check_rate", 15)
+        check_rate = rospy.Rate(self.rate)
+        self.start_test = True  #default when startup run calibrate
+
+        #Publisher to control the robot's speed
+        self.cmd_topic = rospy.get_param("~cmd_topic", '/cmd_vel')
+        self.cmd_vel   = rospy.Publisher(self.cmd_topic, Twist, queue_size=5)
+
+        #The base frame is base_footprint for the robot,odom_frame is odom
+        self.base_frame = rospy.get_param('~base_frame', '/base_footprint')
+        self.odom_frame = rospy.get_param('~odom_frame', '/odom')
+
+        #initialize the tf listener and wait
+        self.tf_listener = tf.TransformListener()
+        rospy.sleep(2)
+
+        #make sure we see the odom and base frames
+        self.tf_listener.waitForTransform(self.odom_frame, self.base_frame, rospy.Time(), rospy.Duration(20.0))
+        self.position = Point()
+
+        #get the starting position from the tf between the odom and base frames
+        self.position = self.get_position()
+        self.x_start  = self.position.x
+        self.y_start  = self.position.y
+
+        #print start calibrate summary info
+        self.print_summary()
+
+        while not rospy.is_shutdown():
+            #get the starting position from the tf between the odom and base frames
+            self.position = self.get_position()
+            check_rate.sleep() #sleep for while loop
+
+            if self.start_test:
+                #compute the euclidean distance from the target point
+                distance = sqrt(pow((self.position.x - self.x_start), 2) +
+                                pow((self.position.y - self.y_start), 2))
+
+                #correct the estimate distance by the correction factor
+                distance *= self.odom_linear_scale
+                error = self.test_distance - distance
+                rospy.loginfo("-->rest_distance: " + str(error))
+
+                move_cmd = Twist()
+                if error < self.tolerance:
+                    self.start_test = False
+                    self.cmd_vel.publish(Twist())  #stop the robot
+                    rospy.logwarn("Now stop move robot !")
+                else:
+                    move_cmd.linear.x = self.speed
+                    self.cmd_vel.publish(move_cmd) #continue move
+            else:  #end test
+                rospy.logwarn("-> linear_scale: " + str(self.odom_linear_scale))
+                actual_dist = input("Please input actual distance:")
+                linear_scale_error = float(actual_dist)/self.test_distance
+                self.odom_linear_scale *= linear_scale_error
+                rospy.logwarn("Now get new linear_scale: " + str(self.odom_linear_scale))
+                self.print_summary()
+                self.start_test = True
+                self.x_start = self.position.x
+                self.y_start = self.position.y
+
+    def print_summary(self):
+        rospy.logwarn("~~~~~~Now Start Linear Speed Calibration~~~~~~")
+        rospy.logwarn("-> test_distance: " + str(self.test_distance))
+        rospy.logwarn("-> linear_speed: "  + str(self.speed))
+        rospy.logwarn("-> move_time: "  + str(self.test_distance/self.speed))
+        rospy.logwarn("-> cmd_topic: "  + str(self.cmd_topic))
+        rospy.logwarn("-> distance_tolerance: " + str(self.tolerance))
+        rospy.logwarn("-> linear_scale: " + str(self.odom_linear_scale))
+
+    #get the current transform between the odom and base frames
+    def get_position(self):
+        try:
+            (trans, rot) = self.tf_listener.lookupTransform(self.odom_frame, self.base_frame, rospy.Time(0))
+        except (tf.Exception, tf.ConnectivityException, tf.LookupException):
+            rospy.logerr("lookup TF exception !")
+            return
+        return Point(*trans)
+
+    #Always stop the robot when shutting down the node
+    def shutdown(self):
+        rospy.logwarn("shutdown test node,stopping the robot")
+        self.cmd_vel.publish(Twist())
+        rospy.sleep(1)
+
+if __name__ == '__main__':
+    try:
+        CalibrateLinear()
+        rospy.spin()
+    except:
+        rospy.logerr("Calibration terminated by unknown problems!")
+

+ 1 - 1
src/teleop_twist_keyboard/teleop_twist_keyboard.py

@@ -82,7 +82,7 @@ if __name__=="__main__":
     pub = rospy.Publisher('cmd_vel', Twist, queue_size = 1)
     rospy.init_node('teleop_twist_keyboard')
 
-    speed = rospy.get_param("~speed", 0.3)
+    speed = rospy.get_param("~speed", 0.12)
     turn = rospy.get_param("~turn", 0.5)
     x = 0
     y = 0