]> defiant.homedns.org Git - ros_wild_thumper.git/commitdiff
avr: calibration from umbmark
authorErik Andresen <erik@vontaene.de>
Tue, 22 Sep 2015 20:44:59 +0000 (22:44 +0200)
committerErik Andresen <erik@vontaene.de>
Tue, 22 Sep 2015 20:44:59 +0000 (22:44 +0200)
avr/motor_ctrl/main.c
avr/motor_ctrl/main.hex
config/base_local_planner_params.yaml
config/control.yaml
scripts/umbmark.py
scripts/wt_node.py

index fbdc1cecd5ed095a1cec4eb3f6f5186c3dfc2283..d40347996ff5d4065a4d1f8f8d5b68642ce55d62 100644 (file)
 #define KI 0.051429
 #define KD 0.000378
 #define PID_T 0.01
-#define STEP_PER_M 4171.4 // wheel diameter=12cm, encoder=48cpr, gear ratio=1:34
-#define WHEEL_DIST 0.252
+#define STEP_PER_M 4171.4 // wheel diameter=12cm, encoder=48cpr, gear ratio=1:34, calculated wheel diameter: 0.12454m
+#define WHEEL_DIST 0.36923 // Real: 0.252
 
 enum mode {
        MOTOR_MANUAL,
index cecc72df2aa334c78e5b8b943a6647e5596255f3..f6c2b4d2ffccbba23553f4c6c35b7a6ebfc698cf 100644 (file)
 :100CE000F8948090E9009090EA00A090EB00B0901A\r
 :100CF000EC006091ED007091EE008091EF0090911A\r
 :100D0000F0001092F10078942BED3FE049E450E4BC\r
-:100D10000E94501025E236E041E85EE30E94501048\r
+:100D10000E94501027EB3BE04DEB5EE30E94501029\r
 :100D200020E030E040E05FE30E945010A501940114\r
 :100D30000E945D0E6B017C01A5019401C501B40107\r
 :100D40000E945D0EA70196010E945C0E23E33BE525\r
 :101020004B015C01B7016C0D7D1D882777FD809514\r
 :10103000982F0E94630F23E33BE542E056E40E94B1\r
 :10104000C80E2B013C01C090B200D090B300E090DC\r
-:10105000B400F090B500A50194010E945C0E25E259\r
-:1010600036E041E85EE30E94C80E9B01AC01C70177\r
+:10105000B400F090B500A50194010E945C0E27EB4E\r
+:101060003BE04DEB5EE30E94C80E9B01AC01C70163\r
 :10107000B6010E945D0E6B017C012BED3FE049EC57\r
 :1010800050E40E944C1018164CF42BED3FE049EC54\r
 :1010900050E4C701B6010E945C0E12C02BED3FE088\r
 :10118000882777FD8095982F0E94630F23E33BE526\r
 :1011900042E056E40E94C80E4B015C016D8D7E8DCD\r
 :1011A000601B710B882777FD8095982F0E94630F35\r
-:1011B00027EB36E64EE455E40E94C80EF894C09240\r
+:1011B00029E935E347E955E40E94C80EF894C09246\r
 :1011C000B200D092B300E092B400F092B500298D45\r
 :1011D0003A8D4B8D5C8D2093BA003093BB004093C9\r
 :1011E000BC005093BD004092B6005092B700609290\r
index 9cc7b79ad5bd8f469ba3ef372c65962648ab2651..3b509c3ee603f5605462b5a1dbc5891e2b7069ce 100644 (file)
@@ -1,13 +1,13 @@
 TrajectoryPlannerROS:
   min_vel_x: 0.1
   max_vel_x: 0.3
-  min_vel_theta: -1.0
-  max_vel_theta: 1.0
+  min_vel_theta: -0.4
+  max_vel_theta: 0.4
   min_in_place_vel_theta: 0.4
 
   acc_lim_x: 2.5
   acc_lim_y: 0.0
-  acc_lim_theta: 3.2
+  acc_lim_theta: 0.3
 
   holonomic_robot: false
   meter_scoring: true
index 97d83a5cad37dad892687d982837a58958c864a7..ea206e90bbab8be7624f2993865bd04ce2d91d1c 100644 (file)
@@ -22,8 +22,8 @@ diff_drive_controller:
   estimate_velocity_from_position: false
 
   # Wheel separation and radius multipliers
-  wheel_separation_multiplier: 1.4696 # default: 1.0
-  wheel_radius_multiplier    : 0.98346 # default: 1.0
+  wheel_separation_multiplier: 1.4126 # default: 1.0
+  wheel_radius_multiplier    : 0.98284 # default: 1.0
 
   # Velocity and acceleration limits
   # Whenever a min_* is unspecified, default to -max_*
index d103b5c0abf277b6afb0f0a9b544f9ce503af549..e6bb5d5394f5360b44cd47e072db5b1d1e038f82 100755 (executable)
@@ -82,7 +82,7 @@ class UMBMark:
                        self.next_pos(2, 0, 0)
                        self.next_pos(0, 0, direction*90*pi/180)
                final_pose = map(operator.sub, self.odom_pose, init_pose)
-               print "Odom Pose: x=%.2f, y=%.2f, angle=%.2f°" % (final_pose[0], final_pose[1], final_pose[2]*180/pi)
+               print "Odom Pose: x=%.3f, y=%.3f, angle=%.3f°" % (final_pose[0], final_pose[1], final_pose[2]*180/pi)
 
        def run_cw(self):
                self.run(-1)
index 96d07689809932aee4722db7e37e4627e25615d8..eb9f8bd9bb138bf74c6ec771d7850b5fa77706c3 100755 (executable)
@@ -151,7 +151,7 @@ class MoveBase:
                odom.pose.covariance[14] = 1e6 # z
                odom.pose.covariance[21] = 1e6 # rotation about X axis
                odom.pose.covariance[28] = 1e6 # rotation about Y axis
-               odom.pose.covariance[35] = 0.1 # rotation about Z axis
+               odom.pose.covariance[35] = 0.03 # rotation about Z axis
 
                # set the velocity
                odom.child_frame_id = "base_footprint"
@@ -163,7 +163,7 @@ class MoveBase:
                odom.twist.covariance[14] = 1e6 # z
                odom.twist.covariance[21] = 1e6 # rotation about X axis
                odom.twist.covariance[28] = 1e6 # rotation about Y axis
-               odom.twist.covariance[35] = 0.1 # rotation about Z axis
+               odom.twist.covariance[35] = 0.03 # rotation about Z axis
 
                # publish the message
                self.pub_odom.publish(odom)