]> defiant.homedns.org Git - ros_wild_thumper.git/commitdiff
tuning
authorErik Andresen <erik@vontaene.de>
Sun, 5 Apr 2015 06:06:42 +0000 (08:06 +0200)
committerErik Andresen <erik@vontaene.de>
Sun, 5 Apr 2015 06:06:42 +0000 (08:06 +0200)
.gitignore [new file with mode: 0644]
launch/teleop.launch
scripts/move_base.py

diff --git a/.gitignore b/.gitignore
new file mode 100644 (file)
index 0000000..0d20b64
--- /dev/null
@@ -0,0 +1 @@
+*.pyc
index 60f4adf4799507c06497a36c226ff95b31658ff5..0de7703beba0d5cdead9232bd3dd09696ca10334 100644 (file)
@@ -1,9 +1,9 @@
 <?xml version="1.0"?>
 <launch>
        <node pkg="turtlebot_teleop" type="turtlebot_teleop_joy" name="turtlebot_teleop_joystick">
-               <param name="scale_linear" value="35"/>
-               <param name="scale_angular" value="25"/>
-               <param name="axis_deadman" value="10"/>
+               <param name="scale_linear" value="25"/>
+               <param name="scale_angular" value="20"/>
+               <param name="axis_deadman" value="3"/>
                <param name="axis_linear" value="1"/>
                <param name="axis_angular" value="0"/>
                <remap from="turtlebot_teleop_joystick/cmd_vel" to="/cmd_vel"/>
index 1188e2c8cd0b8abda78dab2ce154a1fd05c26b05..6886ec0cbfd69a303bcea8ff482c6aa61397ba2d 100755 (executable)
@@ -23,6 +23,11 @@ class MoveBase:
                        rate.sleep()
 
        def set_speed(self, left, right):
+               if left > 0: left+=80
+               elif left < 0: left-=80
+               if right > 0: right+=80
+               elif right < 0: right-=80
+
                if left > 255: left=255
                elif left < -255: left=-255
                if right > 255: right=255