Browse Source

新增红外传感器的消息msg定义

corvin 5 years ago
parent
commit
fa9af94eed

+ 27 - 16
src/robot_navigation/rviz/view_navigation.rviz

@@ -8,9 +8,12 @@ Panels:
         - /TF1/Tree1
         - /TF1/Tree1
         - /Global Map1/Planner1
         - /Global Map1/Planner1
         - /Local Map1/Planner1
         - /Local Map1/Planner1
+        - /Odometry1
+        - /Odometry1/Shape1
+        - /Imu1
         - /Imu1/Axes properties1
         - /Imu1/Axes properties1
       Splitter Ratio: 0.605556011
       Splitter Ratio: 0.605556011
-    Tree Height: 359
+    Tree Height: 663
   - Class: rviz/Selection
   - Class: rviz/Selection
     Name: Selection
     Name: Selection
   - Class: rviz/Tool Properties
   - Class: rviz/Tool Properties
@@ -68,6 +71,11 @@ Visualization Manager:
           Show Axes: false
           Show Axes: false
           Show Trail: false
           Show Trail: false
           Value: true
           Value: true
+        base_imu_link:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
         base_link:
         base_link:
           Alpha: 1
           Alpha: 1
           Show Axes: false
           Show Axes: false
@@ -91,13 +99,15 @@ Visualization Manager:
         All Enabled: false
         All Enabled: false
         base_footprint:
         base_footprint:
           Value: true
           Value: true
+        base_imu_link:
+          Value: true
         base_link:
         base_link:
           Value: true
           Value: true
         lidar:
         lidar:
           Value: true
           Value: true
         map:
         map:
           Value: true
           Value: true
-        odom:
+        odom_combined:
           Value: true
           Value: true
       Marker Scale: 0.300000012
       Marker Scale: 0.300000012
       Name: TF
       Name: TF
@@ -106,11 +116,12 @@ Visualization Manager:
       Show Names: true
       Show Names: true
       Tree:
       Tree:
         map:
         map:
-          odom:
+          odom_combined:
             base_footprint:
             base_footprint:
               base_link:
               base_link:
-                lidar:
-                  {}
+                base_imu_link:
+                  lidar:
+                    {}
       Update Interval: 0
       Update Interval: 0
       Value: true
       Value: true
     - Alpha: 1
     - Alpha: 1
@@ -381,10 +392,10 @@ Visualization Manager:
         Alpha: 1
         Alpha: 1
         Axes Length: 1
         Axes Length: 1
         Axes Radius: 0.100000001
         Axes Radius: 0.100000001
-        Color: 255; 25; 0
-        Head Length: 0.300000012
+        Color: 57; 95; 199
+        Head Length: 0.100000001
         Head Radius: 0.100000001
         Head Radius: 0.100000001
-        Shaft Length: 1
+        Shaft Length: 0.100000001
         Shaft Radius: 0.0500000007
         Shaft Radius: 0.0500000007
         Value: Arrow
         Value: Arrow
       Topic: /odom_ekf
       Topic: /odom_ekf
@@ -437,25 +448,25 @@ Visualization Manager:
   Views:
   Views:
     Current:
     Current:
       Class: rviz/Orbit
       Class: rviz/Orbit
-      Distance: 21.2202759
+      Distance: 6.24388552
       Enable Stereo Rendering:
       Enable Stereo Rendering:
         Stereo Eye Separation: 0.0599999987
         Stereo Eye Separation: 0.0599999987
         Stereo Focal Distance: 1
         Stereo Focal Distance: 1
         Swap Stereo Eyes: false
         Swap Stereo Eyes: false
         Value: false
         Value: false
       Focal Point:
       Focal Point:
-        X: -7.59059811
-        Y: -0.358938813
-        Z: 0.18467477
+        X: -0.350812674
+        Y: 1.04504514
+        Z: -1.69744515
       Focal Shape Fixed Size: true
       Focal Shape Fixed Size: true
       Focal Shape Size: 0.0500000007
       Focal Shape Size: 0.0500000007
       Invert Z Axis: false
       Invert Z Axis: false
       Name: Current View
       Name: Current View
       Near Clip Distance: 0.00999999978
       Near Clip Distance: 0.00999999978
-      Pitch: 1.25979471
+      Pitch: 1.31979465
       Target Frame: <Fixed Frame>
       Target Frame: <Fixed Frame>
       Value: Orbit (rviz)
       Value: Orbit (rviz)
-      Yaw: 1.48496842
+      Yaw: 0.0949685201
     Saved: ~
     Saved: ~
 Window Geometry:
 Window Geometry:
   Displays:
   Displays:
@@ -463,7 +474,7 @@ Window Geometry:
   Height: 876
   Height: 876
   Hide Left Dock: true
   Hide Left Dock: true
   Hide Right Dock: true
   Hide Right Dock: true
-  QMainWindow State: 000000ff00000000fd00000004000000000000016a00000393fc0200000005fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073000000002800000393000000d700ffffff000000010000010f00000393fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000002800000393000000ad00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004a00000003efc0100000002fb0000000800540069006d00650000000000000004a00000030000fffffffb0000000800540069006d00650100000000000004500000000000000000000006400000032600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
+  QMainWindow State: 000000ff00000000fd00000004000000000000016a00000326fc0200000005fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073000000002800000326000000d700ffffff000000010000010f00000393fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000002800000393000000ad00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004a00000003efc0100000002fb0000000800540069006d00650000000000000004a00000030000fffffffb0000000800540069006d00650100000000000004500000000000000000000006400000032600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
   Selection:
   Selection:
     collapsed: false
     collapsed: false
   Time:
   Time:
@@ -474,4 +485,4 @@ Window Geometry:
     collapsed: true
     collapsed: true
   Width: 1600
   Width: 1600
   X: 0
   X: 0
-  Y: 24
+  Y: 204

+ 6 - 0
src/ros_arduino_bridge/ros_arduino_msgs/msg/InfraredSensors.msg

@@ -0,0 +1,6 @@
+# Float message from three infrared sensors IO pin.
+Header header
+
+float64 front_dist
+float64 left_dist
+float64 right_dist

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

@@ -1,7 +1,5 @@
 # For a direct USB cable connection, the port name is typically
 # For a direct USB cable connection, the port name is typically
 # /dev/ttyACM# where is # is a number such as 0, 1, 2, etc
 # /dev/ttyACM# where is # is a number such as 0, 1, 2, etc
-# For a wireless connection like XBee, the port is typically
-# /dev/ttyUSB# where # is a number such as 0, 1, 2, etc.
 
 
 is_use_serial: True
 is_use_serial: True
 
 

+ 2 - 1
src/ros_arduino_bridge/ros_arduino_python/launch/arduino.launch

@@ -1,7 +1,8 @@
 <!--
 <!--
-  Copyright: 2016-2019 ROS小课堂 www.corvin.cn
+  Copyright: 2016-2020 ROS小课堂 www.corvin.cn
   Description:
   Description:
     启动底盘arduino的上位机launch文件.
     启动底盘arduino的上位机launch文件.
+  Author: corvin
   History:
   History:
     20190722: init this file.
     20190722: init this file.
 -->
 -->

+ 1 - 1
src/ros_arduino_bridge/ros_arduino_python/nodes/arduino_node.py

@@ -23,7 +23,7 @@ class ArduinoROS():
 
 
         # Cleanup when termniating the node
         # Cleanup when termniating the node
         rospy.on_shutdown(self.shutdown)
         rospy.on_shutdown(self.shutdown)
-        
+
         self.is_use_serial = rospy.get_param("~is_use_serial", True)
         self.is_use_serial = rospy.get_param("~is_use_serial", True)
 
 
         self.serial_port = rospy.get_param("~serial_port", "/dev/ttyACM0")
         self.serial_port = rospy.get_param("~serial_port", "/dev/ttyACM0")

+ 0 - 18
src/ros_arduino_bridge/ros_arduino_python/src/ros_arduino_python/arduino_sensors.py

@@ -2,21 +2,6 @@
 
 
 """
 """
     Sensor class for the arudino_python package
     Sensor class for the arudino_python package
-
-    Created for the Pi Robot Project: http://www.pirobot.org
-    Copyright (c) 2012 Patrick Goebel.  All rights reserved.
-
-    This program is free software; you can redistribute it and/or modify
-    it under the terms of the GNU General Public License as published by
-    the Free Software Foundation; either version 2 of the License, or
-    (at your option) any later version.
-
-    This program is distributed in the hope that it will be useful,
-    but WITHOUT ANY WARRANTY; without even the implied warranty of
-    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-    GNU General Public License for more details at:
-
-    http://www.gnu.org/licenses/gpl.html
 """
 """
 
 
 import roslib; roslib.load_manifest('ros_arduino_python')
 import roslib; roslib.load_manifest('ros_arduino_python')
@@ -218,9 +203,6 @@ class GP2Y0A41(IRSensor):
     def read_value(self):
     def read_value(self):
         value = self.controller.analog_read(self.pin)
         value = self.controller.analog_read(self.pin)
 
 
-        if value < 16:
-            value = 16
-
         dist = 20.76/(value - 11.0)
         dist = 20.76/(value - 11.0)
 
 
         # If we get a spurious reading, set it to the max_range
         # If we get a spurious reading, set it to the max_range