Parcourir la source

更新小车最新角速度,线速度标定参数

corvin il y a 5 ans
Parent
commit
a866f444d2

+ 2 - 2
src/robot_calibration/config/angular_calibrate_params.yaml

@@ -25,10 +25,10 @@
 #      将角速度从0.5rad/s改为0.2rad/s,tolerance_angel从0.03->0.05.
 #######################################################################
 test_circle: 2 #test run circle
-angular_speed: 0.2  #default 0.2rad/s
+angular_speed: 0.5  #default 0.2rad/s
 tolerance_angle: 0.04 #tolerance radians
 angular_scale: 1.00
 check_odom_rate: 15 #check odom rate
 cmd_topic: /cmd_vel
 base_frame: base_footprint
-odom_frame: odom
+odom_frame: odom_combined

+ 2 - 5
src/robot_calibration/launch/calibrate_mobilebase_angular.launch

@@ -9,11 +9,8 @@
     20180425: init this file.
 -->
 <launch>
-  <!--startup robot urdf description file-->
-  <include file="$(find robot_description)/launch/robot_description.launch" />
-
-  <!--startup mobilebase arduino launch -->
-  <include file="$(find ros_arduino_python)/launch/arduino.launch" />
+  <!--startup robot bringup file-->
+  <include file="$(find robot_bringup)/launch/robot_bringup.launch" />
 
   <node pkg="robot_calibration" type="calibrate_mobilebase_angular.py" name="calibrate_angular_node" output="screen" >
     <rosparam file="$(find robot_calibration)/config/angular_calibrate_params.yaml" command="load" />

+ 1 - 1
src/robot_calibration/src/calibrate_mobilebase_angular.py

@@ -81,7 +81,7 @@ class CalibrateAngular():
 
             # Get base frame and odom frame
             self.base_frame = rospy.get_param('~base_frame', '/base_footprint')
-            self.odom_frame = rospy.get_param('~odom_frame', '/odom')
+            self.odom_frame = rospy.get_param('~odom_frame', '/odom_combined')
         except:
             rospy.logerr("ERROR: Get config param error from yaml file...")
 

+ 2 - 2
src/ros_arduino_bridge/ros_arduino_python/config/my_arduino_params.yaml

@@ -24,11 +24,11 @@ odom_name: odom
 
 # === Robot drivetrain parameters
 wheel_diameter: 0.058
-wheel_track: 0.114     #L value
+wheel_track: 0.1104    #L value
 encoder_resolution: 11 #12V DC motors
 gear_reduction: 46     #empty payload rpm 130r/m
 debugPID: False
-linear_scale_correction: 0.9886
+linear_scale_correction: 0.974
 angular_scale_correction: 1.00
 
 # === PID parameters