Browse Source

更新红外demo程序,使其可以流畅的运行

corvin rasp melodic 2 years ago
parent
commit
d4cf08d57b

+ 1 - 3
src/robot_demo/cfg/param.yaml

@@ -1,10 +1,8 @@
 #####################################################
-#  
 # Description:测试红外小程序
 #   center_dist:红外测距时悬停的距离.
 # Author: adam_zhuo
 # History:
 #   20210512:init this file.
 ######################################################
-
-center_dist: 0.15
+center_dist: 0.12

+ 12 - 12
src/robot_demo/cfg/view_demo.rviz

@@ -5,7 +5,7 @@ Panels:
     Property Tree Widget:
       Expanded: ~
       Splitter Ratio: 0.5
-    Tree Height: 605
+    Tree Height: 356
   - Class: rviz/Selection
     Name: Selection
   - Class: rviz/Tool Properties
@@ -178,33 +178,33 @@ Visualization Manager:
   Views:
     Current:
       Class: rviz/Orbit
-      Distance: 1.9625797271728516
+      Distance: 1.8301275968551636
       Enable Stereo Rendering:
         Stereo Eye Separation: 0.05999999865889549
         Stereo Focal Distance: 1
         Swap Stereo Eyes: false
         Value: false
       Focal Point:
-        X: 0.20904195308685303
-        Y: 0.3309887647628784
-        Z: 0.16701556742191315
+        X: 0.25102823972702026
+        Y: 0.40160438418388367
+        Z: 0.17577525973320007
       Focal Shape Fixed Size: true
       Focal Shape Size: 0.05000000074505806
       Invert Z Axis: false
       Name: Current View
       Near Clip Distance: 0.009999999776482582
-      Pitch: 1.2747960090637207
+      Pitch: 0.5147963762283325
       Target Frame: <Fixed Frame>
       Value: Orbit (rviz)
-      Yaw: 0.08499996364116669
+      Yaw: 5.50818395614624
     Saved: ~
 Window Geometry:
   Displays:
     collapsed: true
-  Height: 930
+  Height: 914
   Hide Left Dock: true
   Hide Right Dock: true
-  QMainWindow State: 000000ff00000000fd00000004000000000000016a000002f3fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006500fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730000000044000002f3000000de00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f0000029ffc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0056006900650077007300000000440000029f000000b900fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b000000044fc0100000002fb0000000800540069006d00650100000000000004b00000028000fffffffb0000000800540069006d00650100000000000004500000000000000000000004b0000002f300000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
+  QMainWindow State: 000000ff00000000fd00000004000000000000016a000002f3fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006500fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730000000044000002f3000000de00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f0000029ffc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0056006900650077007300000000440000029f000000b900fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004a300000044fc0100000002fb0000000800540069006d00650100000000000004a30000028000fffffffb0000000800540069006d00650100000000000004500000000000000000000004a3000002e300000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
   Selection:
     collapsed: false
   Time:
@@ -213,6 +213,6 @@ Window Geometry:
     collapsed: false
   Views:
     collapsed: true
-  Width: 1200
-  X: 37
-  Y: 3
+  Width: 1187
+  X: 42
+  Y: 62

+ 5 - 2
src/robot_demo/launch/infrared_demo.launch

@@ -5,10 +5,13 @@
  * @History: 20210429:初始化文件-adam_zhuo
 -->
 <launch>
-  <!-- 加载参数 -->
+  <!-- load param -->
   <arg name="cfg_file" default="$(find robot_demo)/cfg/param.yaml" />
 
-  <!-- 启动robot_demo_infrared_node -->
+  <!-- launch robot_bringup.launch -->
+  <include file="$(find robot_bringup)/launch/robot_bringup.launch" />
+
+  <!-- run robot_demo_infrared_node -->
   <node pkg="robot_demo" type="robot_demo_infrared_node" name="robot_demo_infrared_node" output="screen">
     <rosparam file="$(arg cfg_file)" command="load" />
   </node>

+ 16 - 16
src/robot_demo/src/infrared_demo_node.cpp

@@ -6,15 +6,14 @@
  */
 #include <infrared_demo.h>
 
-Infrared_Demo::Infrared_Demo(){
-
+Infrared_Demo::Infrared_Demo()
+{
     //从参数服务器中取“center_dist”数据
     ros::param::param<float>("~center_dist", center_dist, 0.2);
-
     //订阅红外数据
     _infrared_sub = nh.subscribe<ros_arduino_msgs::InfraredSensors>("/mobilebase_arduino/sensor/GP2Y0A41", 1, &Infrared_Demo::infrared_callback, this);
     //注册小车速度发布者
-    _cmd_vel_pub = nh.advertise<geometry_msgs::Twist>("/cmd_vel", 1);
+    _cmd_vel_pub = nh.advertise<geometry_msgs::Twist>("/cmd_vel", 2);
 }
 
 Infrared_Demo::~Infrared_Demo(){
@@ -23,31 +22,32 @@ Infrared_Demo::~Infrared_Demo(){
 /**
  * @description: 订阅红外数据回调函数
  */
-void Infrared_Demo::infrared_callback(const ros_arduino_msgs::InfraredSensors::ConstPtr &data){
-
+void Infrared_Demo::infrared_callback(const ros_arduino_msgs::InfraredSensors::ConstPtr &data)
+{
     //获取前红外信息
     float front_dist = data->front_dist;
-
     //根据前红外反馈的距离来控制小车运动,离小车较远时小车前进,离小车较近时小车后退
-    if(front_dist > 0.28){
+    if(front_dist > 0.28)
+    {
         _twist.linear.x = 0;
         _cmd_vel_pub.publish(_twist);
-    }else{
+    }
+    else
+    {
         float err_dist = front_dist - center_dist;
-        _twist.linear.x = 0.74 * err_dist * 2;
-        if(abs(_twist.linear.x) < 0.015){
+        _twist.linear.x = 3.0 * err_dist;
+        if(abs(_twist.linear.x) < 0.1)
+        {
             _twist.linear.x = 0;
         }
         _cmd_vel_pub.publish(_twist);
     }
 }
 
-int main(int argc, char **argv){
-
-    //初始化节点
+int main(int argc, char **argv)
+{
     ros::init(argc, argv, "infrared_demo_node");
     //根据Infrafed_Demo声明对象,调用构造函数
     Infrared_Demo infrared_demo;
-    //使ROS中回调函数生效
     ros::spin();
-}
+}

+ 1 - 1
src/ros_arduino_bridge/ros_arduino_python/cfg/my_arduino_params.yaml

@@ -65,7 +65,7 @@ BWheel_Ko: 10
 
 # Sensor definitions (case sensitive!):
 sensors: {
-  GP2Y0A41: {pin: 0, type: GP2Y0A41, rate: 5},
+  GP2Y0A41: {pin: 0, type: GP2Y0A41, rate: 8},
   batPercent: {pin: 0, type: BAT_PERCENT, rate: 0.1},
 }
 

+ 1 - 1
update_code.sh

@@ -23,7 +23,7 @@ echo -e "\n"
 
 sleep 3
 echo -e "${green}>>> 2: 开始编译代码${normal}"
-rm -rf .ros/log/
+rm -rf ~/.ros/log/
 catkin_make
 
 cd src/dual_iic/build