< >
Home » Turtlebot3代码解读 » Turtlebot3代码解读-turtlebot3_core

Turtlebot3代码解读-turtlebot3_core

Turtlebot3代码解读-turtlebot3_core

说明:

  • 介绍turtlebot3核心功能固件库实现

代码库:

  • https://github.com/ncnynl/turtlebot3/tree/master/turtlebot3_core

代码目录结构:

├── CMakeLists.txt
├── firmware
│   ├── libraries
│   │   └── ros_lib
│   │       ├── ArduinoHardware.h                #定义针对不同Arduino开发板及通讯方式和波特率
│   │       ├── duration.cpp                     #持续时间(时间段)类实现
│   │       ├── geometry_msgs                    #实现对速度,位姿等里程相关消息的头文件
│   │       │   ├── Accel.h
│   │       │   ├── AccelStamped.h
│   │       │   ├── AccelWithCovariance.h
│   │       │   ├── AccelWithCovarianceStamped.h
│   │       │   ├── Inertia.h
│   │       │   ├── InertiaStamped.h
│   │       │   ├── Point32.h
│   │       │   ├── Point.h
│   │       │   ├── PointStamped.h
│   │       │   ├── Polygon.h
│   │       │   ├── PolygonStamped.h
│   │       │   ├── Pose2D.h
│   │       │   ├── PoseArray.h
│   │       │   ├── Pose.h
│   │       │   ├── PoseStamped.h
│   │       │   ├── PoseWithCovariance.h
│   │       │   ├── PoseWithCovarianceStamped.h
│   │       │   ├── Quaternion.h
│   │       │   ├── QuaternionStamped.h
│   │       │   ├── Transform.h
│   │       │   ├── TransformStamped.h
│   │       │   ├── Twist.h
│   │       │   ├── TwistStamped.h
│   │       │   ├── TwistWithCovariance.h
│   │       │   ├── TwistWithCovarianceStamped.h
│   │       │   ├── Vector3.h
│   │       │   ├── Vector3Stamped.h
│   │       │   ├── Wrench.h
│   │       │   └── WrenchStamped.h
│   │       ├── nav_msgs                         #实现对地图,目标,路径等导航相关消息的头文件
│   │       │   ├── GetMapActionFeedback.h
│   │       │   ├── GetMapActionGoal.h
│   │       │   ├── GetMapAction.h
│   │       │   ├── GetMapActionResult.h
│   │       │   ├── GetMapFeedback.h
│   │       │   ├── GetMapGoal.h
│   │       │   ├── GetMap.h
│   │       │   ├── GetMapResult.h
│   │       │   ├── GetPlan.h
│   │       │   ├── GridCells.h
│   │       │   ├── MapMetaData.h
│   │       │   ├── OccupancyGrid.h
│   │       │   ├── Odometry.h
│   │       │   ├── Path.h
│   │       │   └── SetMap.h
│   │       ├── ros                              #ROS核心功能,实现节点句柄,发布,服务,订阅,时间相关的头文件
│   │       │   ├── duration.h
│   │       │   ├── msg.h
│   │       │   ├── node_handle.h
│   │       │   ├── publisher.h
│   │       │   ├── service_client.h
│   │       │   ├── service_server.h
│   │       │   ├── subscriber.h
│   │       │   └── time.h
│   │       ├── roscpp                          #roscpp功能,日志相关头文件
│   │       │   ├── Empty.h
│   │       │   ├── GetLoggers.h
│   │       │   ├── Logger.h
│   │       │   └── SetLoggerLevel.h
│   │       ├── ros.h                           #ros.h头文件
│   │       ├── rosserial_arduino               #与arduino串口通讯的消息的头文件
│   │       │   ├── Adc.h
│   │       │   └── Test.h
│   │       ├── rosserial_msgs                  #实现串口相关消息的头文件
│   │       │   ├── Log.h
│   │       │   ├── RequestMessageInfo.h
│   │       │   ├── RequestParam.h
│   │       │   ├── RequestServiceInfo.h
│   │       │   └── TopicInfo.h
│   │       ├── sensor_msgs                     #传感器相关消息的头文件
│   │       │   ├── BatteryState.h
│   │       │   ├── CameraInfo.h
│   │       │   ├── ChannelFloat32.h
│   │       │   ├── CompressedImage.h
│   │       │   ├── FluidPressure.h
│   │       │   ├── Illuminance.h
│   │       │   ├── Image.h
│   │       │   ├── Imu.h
│   │       │   ├── JointState.h
│   │       │   ├── JoyFeedbackArray.h
│   │       │   ├── JoyFeedback.h
│   │       │   ├── Joy.h
│   │       │   ├── LaserEcho.h
│   │       │   ├── LaserScan.h
│   │       │   ├── MagneticField.h
│   │       │   ├── MultiDOFJointState.h
│   │       │   ├── MultiEchoLaserScan.h
│   │       │   ├── NavSatFix.h
│   │       │   ├── NavSatStatus.h
│   │       │   ├── PointCloud2.h
│   │       │   ├── PointCloud.h
│   │       │   ├── PointField.h
│   │       │   ├── Range.h
│   │       │   ├── RegionOfInterest.h
│   │       │   ├── RelativeHumidity.h
│   │       │   ├── SetCameraInfo.h
│   │       │   ├── Temperature.h
│   │       │   └── TimeReference.h
│   │       ├── std_msgs                     #标准消息的相关头文件
│   │       │   ├── Bool.h
│   │       │   ├── Byte.h
│   │       │   ├── ByteMultiArray.h
│   │       │   ├── Char.h
│   │       │   ├── ColorRGBA.h
│   │       │   ├── Duration.h
│   │       │   ├── Empty.h
│   │       │   ├── Float32.h
│   │       │   ├── Float32MultiArray.h
│   │       │   ├── Float64.h
│   │       │   ├── Float64MultiArray.h
│   │       │   ├── Header.h
│   │       │   ├── Int16.h
│   │       │   ├── Int16MultiArray.h
│   │       │   ├── Int32.h
│   │       │   ├── Int32MultiArray.h
│   │       │   ├── Int64.h
│   │       │   ├── Int64MultiArray.h
│   │       │   ├── Int8.h
│   │       │   ├── Int8MultiArray.h
│   │       │   ├── MultiArrayDimension.h
│   │       │   ├── MultiArrayLayout.h
│   │       │   ├── String.h
│   │       │   ├── Time.h
│   │       │   ├── UInt16.h
│   │       │   ├── UInt16MultiArray.h
│   │       │   ├── UInt32.h
│   │       │   ├── UInt32MultiArray.h
│   │       │   ├── UInt64.h
│   │       │   ├── UInt64MultiArray.h
│   │       │   ├── UInt8.h
│   │       │   └── UInt8MultiArray.h
│   │       ├── std_srvs                   #标准服务的相关头文件
│   │       │   ├── Empty.h
│   │       │   ├── SetBool.h
│   │       │   └── Trigger.h
│   │       ├── tf                         #定义TF相关头文件
│   │       │   ├── FrameGraph.h
│   │       │   ├── tf.h
│   │       │   ├── tfMessage.h
│   │       │   └── transform_broadcaster.h
│   │       ├── tf2_msgs                    #定义TF2消息的相关头文件
│   │       │   ├── FrameGraph.h
│   │       │   ├── LookupTransformActionFeedback.h
│   │       │   ├── LookupTransformActionGoal.h
│   │       │   ├── LookupTransformAction.h
│   │       │   ├── LookupTransformActionResult.h
│   │       │   ├── LookupTransformFeedback.h
│   │       │   ├── LookupTransformGoal.h
│   │       │   ├── LookupTransformResult.h
│   │       │   ├── TF2Error.h
│   │       │   └── TFMessage.h
│   │       ├── time.cpp                    #时间类实现
│   │       └── turtlebot3_msgs             #turtlebot3的消息的相关头文件
│   │           ├── MotorPower.h
│   │           ├── SensorState.h
│   │           └── VersionInfo.h
│   ├── turtlebot3_core_config.h    #核心头文件,定义相关配置变量和函数
│   ├── turtlebot3_core.ino         #核心实现
│   ├── turtlebot3_motor_driver.cpp #电机驱动实现
│   └── turtlebot3_motor_driver.h   #电机驱动头文件
└── package.xml

重要文件说明:

turtlebot3_core_config.h

  • 头文件,定义相关的配置变量
  • 定义与传感器间的通讯频率为10hz
  • 定义轮半径(单位米),轮间隔(单位米)和编码器最大范围值
  • 定义默认速度,线速度和角速度
  • 定义脉冲和度的转换
  • 定义度和周长的互换函数
  • 定义速度回调函数
  • 定义多个发布函数,imu,传感器状态,驱动
  • 定义更新函数,odom,关节,TF

turtlebot3_core.ino

  • 实现turtlebot3_core_config.h定义的函数

turtlebot3_motor_driver.h

  • 加载DynamixelSDK.h头文件
  • 定义电机相关参数
  • 定义函数:扭矩设置,读取编码器,速度控制

turtlebot3_motor_driver.cpp

  • 实现turtlebot3_motor_driver.h定义的函数

纠错,疑问,交流: 请进入讨论区点击加入Q群

获取最新文章: 扫一扫右上角的二维码加入“创客智造”公众号


标签: turtlebot3代码解读