Pārlūkot izejas kodu

更新走迷宫代码

corvin_zhang 4 gadi atpakaļ
vecāks
revīzija
3a54c29b3c

+ 2 - 2
src/infrared_maze/cfg/param.yaml

@@ -8,8 +8,8 @@
 ######################################################
 infrared_topic: /mobilebase_arduino/sensor/GP2Y0A41
 cmd_topic: /cmd_vel
-linear_x: 0.18
-linear_y: 0.16
+linear_x: 0.17
+linear_y: 0.15
 angular_speed: 0.4
 warn_dist: 0.12
 tolerance_dist: 0.05

+ 20 - 8
src/infrared_maze/src/infrared_maze.cpp

@@ -60,19 +60,19 @@ void horizontallyMoveMiddle(float left_dis,float right_dis,float tolerance)
 {
     float diff = left_dis - right_dis;
     //ROS_INFO("left right diff:%f", diff);
-    if(fabs(diff) > tolerance)
+    if((fabs(diff) > tolerance)&&(left_dis != 0.300000)&&(right_dis != 0.300000))
     {
         if(diff < 0) //move right
         {
-            ROS_INFO("move right horizontally !");
+            ROS_WARN("move Right horizontally !");
             publishTwistCmd(0, -linear_y_speed, 0);
         }
         else //move left
         {
-            ROS_INFO("move left horizontally !");
+            ROS_WARN("move Left horizontally !");
             publishTwistCmd(0, linear_y_speed, 0);
         }
-        ros::Duration(0.1).sleep(); //100 ms
+        ros::Duration(0.2).sleep(); //delay 200 ms
     }
     else //stop move
     {
@@ -151,8 +151,8 @@ int controlTurn(int flag)
         last_angle = rotation;
         //ROS_INFO("turn_angle:%f",turn_angle);
     }
-    ros::Duration(0.2).sleep(); //200 ms
     ROS_INFO("Turning finish !!!");
+    ros::Duration(0.3).sleep(); //300 ms
 
     return 0;
 }
@@ -165,24 +165,36 @@ void checkInfraredDist(float infrared_f,float infrared_l,float infrared_r,
 {
     if(infrared_f < warn_dist*2.0) //前边距离小于警告值
     {
+        if(infrared_l > infrared_r)
+        {
+            ROS_WARN("turn Left !");
+            controlTurn(TURN_LEFT);
+        }
+        else if(infrared_l < infrared_r)
+        {
+            ROS_WARN("turn Right !");
+            controlTurn(TURN_RIGHT);
+        }
+#if 0
         if(fabs(infrared_l - infrared_r) > tolerance)
         {
             if(infrared_l > infrared_r)
             {
-                ROS_WARN("turn left !");
+                ROS_WARN("turn Left !");
                 controlTurn(TURN_LEFT);
             }
             else if(infrared_l < infrared_r)
             {
-                ROS_WARN("turn right !");
+                ROS_WARN("turn Right !");
                 controlTurn(TURN_RIGHT);
             }
         }
         else
         {
-            ROS_WARN("turn back !");
+            ROS_WARN("turn Back !");
             controlTurn(TURN_BACK);
         }
+#endif
     }
     else
     {

+ 1 - 1
src/robot_calibration/launch/calibrate_mobilebase_linear.launch

@@ -6,7 +6,7 @@
    参数,从而可以减小该误差,使小车底盘移动距离更准确,为后面的自动导航做好准备工作.
    该启动文件主要启动流程如下:
    1.启动小车的robot_bringup文件,这样一下启动所有必要launch文件.
-   3.启动标定程序,从配置文件中读取测试移动距离、移动速度、控制移动的话题等配置信息.
+   2.启动标定程序,从配置文件中读取测试移动距离、移动速度、控制移动的话题等配置信息.
      根据该信息来控制小车移动,测试完成后,需要拿出米尺来测量小车的实际移动距离与配置
      的移动距离的差值,然后标定程序会根据测量值来修正配置参数,直到实际的移动距离与配
      置的移动距离之间的误差在可容忍范围内即可.最后的linear_scale参数就是最终的标定参数,

+ 2 - 2
src/robot_calibration/src/calibrate_mobilebase_linear.py

@@ -2,8 +2,7 @@
 # -*- coding: UTF-8 -*-
 
 """
- Copyright: 2016-2018 ROS小课堂 www.corvin.cn
- Author: corvin
+ Copyright: 2016-2020 ROS小课堂 www.corvin.cn
  Description:
   该源码文件是标定三轮全向移动小车的底盘线速度的代码,标定的主要过程
   就是根据设定的移动距离,然后向小车的移动话题中发布移动速度.在此时,
@@ -11,6 +10,7 @@
   系之间的距离已经小于容忍范围内,说明小车已经到了指定的移动距离.
   此时就需要测量小车的实际移动距离跟坐标系间检测的距离是否一样,
   两者之间的误差是否可以接受,如果不接受就需要修改里程计的修正值.
+ Author: corvin
  History:
   20180907: initial this file.
 """

+ 9 - 10
src/ros_arduino_bridge/ros_arduino_python/config/my_arduino_params.yaml

@@ -24,27 +24,28 @@ rate: 25
 
 cmd_topic: cmd_vel
 
-base_controller_rate: 20.0
+base_controller_rate: 10.0
 base_controller_timeout: 0.7
 
 # For a robot that uses base_footprint, change base_frame to base_footprint
 base_frame: base_footprint
 odom_name: odom
 
-# === Robot drivetrain parameters
+# Robot drivetrain parameters
 wheel_diameter: 0.058
 wheel_track: 0.1104    #L value
 encoder_resolution: 11 #12V DC motors
-gear_reduction: 46     #empty payload rpm 130r/m
-debugPID: False
+gear_reduction: 46     #empty payload rpm 130 r/m
 linear_scale_correction: 0.974
 angular_scale_correction: 1.00
 
 # === PID parameters
+debugPID: False
+
 accel_limit: 0.05
 
-AWheel_Kp: 15
-AWheel_Kd: 15
+AWheel_Kp: 25
+AWheel_Kd: 34
 AWheel_Ki: 0
 AWheel_Ko: 50
 
@@ -53,14 +54,12 @@ BWheel_Kd: 15
 BWheel_Ki: 0
 BWheel_Ko: 50
 
-CWheel_Kp: 15
+CWheel_Kp: 18
 CWheel_Kd: 15
 CWheel_Ki: 0
 CWheel_Ko: 50
 
-# === Sensor definitions.Sensor type can be one of the follow (case sensitive!):
-#  * Analog
-#  * Digital
+# Sensor definitions (case sensitive!):
 sensors: {
   GP2Y0A41: {pin: 0, type: GP2Y0A41, rate: 5, direction: input},
   batPercent: {pin: 0, type: BAT_PERCENT, rate: 0.1, direction: input},

+ 4 - 4
src/voice_system/iflytek_offline_tts/src/iflytek_offline_tts.cpp

@@ -19,7 +19,7 @@
 
 
 static char voicePath[] = "/tmp/say.wav";
-static char playPath[] = "play /tmp/say.wav";
+static char playPath[] = "play -q --multi-threaded /tmp/say.wav";
 static std::string appID = "5d5b9efd";
 
 typedef int SR_DWORD;
@@ -100,7 +100,7 @@ int text_to_speech(const char* src_text, const char* des_path, const char* param
 		fclose(fp);
 		return ret;
 	}
-	ROS_INFO("making wave file...");
+	//ROS_INFO("making wave file...");
 	fwrite(&wav_hdr, sizeof(wav_hdr) ,1, fp); //添加wav音频头,使用采样率为16000
 	while (1)
 	{
@@ -167,7 +167,7 @@ int startOfflineTTS(const char *text, const char *filename, const char *pAppid)
             fo|/home/corvin/blackTornadoRobot/src/voice_system/iflytek_offline_tts/config/common.jet,\
             sample_rate=16000, volume=50, pitch=50, rdn=0, effect=0");
 
-    ROS_INFO("session_begin_params:%s", session_begin_params);
+    //ROS_INFO("session_begin_params:%s", session_begin_params);
 
     ret = MSPLogin(NULL, NULL, login_params);
     if(MSP_SUCCESS != ret)
@@ -177,7 +177,7 @@ int startOfflineTTS(const char *text, const char *filename, const char *pAppid)
     }
 
 	/* 文本合成 */
-	ROS_INFO("start make wav file...");
+	//ROS_INFO("start make wav file...");
 	ret = text_to_speech(text, filename, session_begin_params);
 	if (MSP_SUCCESS != ret)
 	{