Browse Source

为各代码增加注释头

corvin 5 years ago
parent
commit
b43d17a9ad

+ 11 - 1
rasp_imu_hat_6dof/launch/imu_data_pub.launch

@@ -1,7 +1,17 @@
+<!---
+  Copyright:2016-2019 https://www.corvin.cn ROS小课堂
+  Author: corvin
+  Description:该launch启动文件是为了启动扩展板,使其进入正常工作状态。启动后,就会在
+    /imu话题上发布imu传感器信息。需要该信息的节点,订阅该话题即可。同时,我们还可以使
+    用dynamic_reconfigure来动态的修正z轴的角度。
+  History:
+    20191031:Initial this launch file.
+--->
 <launch>
   <arg name="imu_cfg_file" default="$(find rasp_imu_hat_6dof)/cfg/param.yaml"/>
+
   <node pkg="rasp_imu_hat_6dof" type="imu_node.py" name="imu_node" output="screen">
-    <rosparam file="$(arg imu_cfg_file)" command="load"/>
+      <rosparam file="$(arg imu_cfg_file)" command="load"/>
   </node>
 </launch>
 

+ 8 - 0
rasp_imu_hat_6dof/launch/imu_rviz_display.launch

@@ -1,3 +1,11 @@
+<!---
+  Copyright:2016-2019 https://www.corvin.cn ROS小课堂
+  Author: corvin
+  Description:该launch启动文件是为了在启动扩展板,使其进入正常工作状态后。
+    可以在rviz中可视化imu扩展板当前的姿态信息。
+  History:
+    20191031:Initial this launch file.
+--->
 <launch>
   <node pkg="rviz" type="rviz" name="imu_rviz_node" 
         args="-d $(find rasp_imu_hat_6dof)/cfg/imu_display.rviz">

+ 10 - 0
rasp_imu_hat_6dof/nodes/imu_data.py

@@ -1,4 +1,13 @@
 #!/usr/bin/env python
+# -*- coding: UTF-8 -*-
+
+# Copyright: 2016-2019 https://www.corvin.cn ROS小课堂
+# Author: corvin
+# Description: 为树莓派IMU扩展板所使用的配套代码,由于默认
+#    扩展板与树莓派使用IIC连接。所以这里的代码是直接从IIC接口
+#    中读取IMU模块的三轴加速度、角度、四元数。
+# History:
+#    20191031: Initial this file.
 
 import smbus
 import numpy as np
@@ -49,3 +58,4 @@ class MyIMU(object):
             self.raw_q1 = float((np.short((q1[1]<<8)|q1[0]))/32768.0)
             self.raw_q2 = float((np.short((q2[1]<<8)|q2[0]))/32768.0)
             self.raw_q3 = float((np.short((q3[1]<<8)|q3[0]))/32768.0)
+

+ 14 - 1
rasp_imu_hat_6dof/nodes/imu_node.py

@@ -1,4 +1,16 @@
 #!/usr/bin/env python
+# -*- coding: UTF-8 -*-
+
+# Copyright: 2016-2019 https://www.corvin.cn ROS小课堂
+# Author: corvin
+# Description: 为树莓派IMU扩展板所使用的配套代码,由于默认
+#    扩展板与树莓派使用IIC连接。所以这里的代码是直接从IIC接口
+#    中读取IMU模块的三轴加速度、角度、四元数,然后组装成ROS
+#    中的IMU消息格式,发布到/imu话题中,这样有需要的节点可以
+#    直接订阅该话题即可获取到imu扩展板当前的数据。
+# History:
+#    20191031: Initial this file.
+
 
 import rospy
 import string
@@ -68,7 +80,8 @@ imuMsg.linear_acceleration_covariance = [
 ]
 
 seq=0
-accel_factor = 9.806/256.0    # sensor reports accel as 256.0 = 1G (9.8m/s^2). Convert to m/s^2.
+# sensor reports accel as 256.0 = 1G (9.8m/s^2). Convert to m/s^2.
+accel_factor = 9.806/256.0
 
 
 myIMU = MyIMU(0x50)