JallyZhang пре 4 година
родитељ
комит
d071cb56b7

+ 16 - 2
src/ros_arduino_bridge/ros_arduino_python/src/ros_arduino_python/base_controller.py

@@ -1,7 +1,13 @@
 #!/usr/bin/env python
+#-*- coding:utf-8 -*-
 
 """
-    A base controller class for the Arduino microcontroller
+  Copyright: 2016-2020 www.corvin.cn ROS小课堂
+  Description:  A base controller class for the Arduino DUE microcontroller
+  Author: corvin
+  History:
+      20200704:当超过给下位机发送控制移动命令时间后,不需要再发送pwm控制0的命令.
+        因为在arduino代码会根据超时自己会执行pwm清零停止电机移动的命令.
 """
 import os
 import rospy
@@ -14,6 +20,7 @@ from nav_msgs.msg import Odometry
 from tf.broadcaster import TransformBroadcaster
 from std_msgs.msg import Int32
 
+
 """ Class to receive Twist commands and publish wheel Odometry data """
 class BaseController:
     
@@ -165,7 +172,14 @@ class BaseController:
                     rospy.logerr("Encoder exception count: " + str(self.bad_encoder_count))
                     return
 
-            # Calculate odometry
+            #当读取到最新的编码器计数为0,说明下位机已经将计数清零,那上位机保存的上一次编码器计数也得清零
+            if aWheel_enc == 0:
+                self.enc_A = 0
+
+            if bWheel_enc == 0:
+                self.enc_B = 0
+
+            #根据编码器两次反馈的差值来计算车轮移动的距离
             dist_A = (aWheel_enc - self.enc_A)/self.ticks_per_meter
             dist_B = (bWheel_enc - self.enc_B)/self.ticks_per_meter
 

+ 0 - 52
src/teleop_twist_keyboard/README.md

@@ -1,52 +0,0 @@
-# teleop_twist_keyboard
-Generic Keyboard Teleop for ROS
-
-# Launch
-Run.
-```
-rosrun teleop_twist_keyboard teleop_twist_keyboard.py
-```
-
-With custom values.
-```
-rosrun teleop_twist_keyboard teleop_twist_keyboard.py _speed:=0.2 _turn:=0.8
-```
-
-Publishing to a different topic (in this case `cmd_vel`).
-```
-rosrun teleop_twist_keyboard teleop_twist_keyboard.py cmd_vel:=cmd_vel
-```
-
-# Usage
-```
-Reading from the keyboard  and Publishing to Twist!
----------------------------
-Moving around:
-   u    i    o
-   j    k    l
-   m    ,    .
-
-For Holonomic mode (strafing), hold down the shift key:
----------------------------
-   U    I    O
-   J    K    L
-   M    <    >
-
-t : up (+z)
-b : down (-z)
-
-anything else : stop
-
-q/z : increase/decrease max speeds by 10%
-w/x : increase/decrease only linear speed by 10%
-e/c : increase/decrease only angular speed by 10%
-4/5 : increase/decrease gripper angle by 5°
-
-1 : arm go up
-2 : arm go dowm
-4 : open the gripper
-5 : close the gripper
-
-CTRL-C to quit
-"""
-