00001 #!/usr/bin/env python 00002 00003 # Software License Agreement (BSD License) 00004 # 00005 # Copyright (c) 2019, Dataspeed Inc. 00006 # All rights reserved. 00007 # 00008 # Redistribution and use in source and binary forms, with or without modification, 00009 # are permitted provided that the following conditions are met: 00010 # 00011 # * Redistributions of source code must retain the above copyright notice, 00012 # this list of conditions and the following disclaimer. 00013 # * Redistributions in binary form must reproduce the above copyright notice, 00014 # this list of conditions and the following disclaimer in the documentation 00015 # and/or other materials provided with the distribution. 00016 # * Neither the name of Dataspeed Inc. nor the names of its 00017 # contributors may be used to endorse or promote products derived from this 00018 # software without specific prior written permission. 00019 # 00020 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND 00021 # ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 00022 # WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 00023 # DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 00024 # FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 00025 # DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 00026 # SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00027 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 00028 # OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 00029 # OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00030 00031 import rospy 00032 from dbw_mkz_msgs.msg import WheelPositionReport, FuelLevelReport 00033 from math import fabs 00034 00035 class WheelCountsPerKm: 00036 def __init__(self): 00037 rospy.init_node('wheel_counts_per_km') 00038 00039 # Variables 00040 self.wheel_position_old = 0 00041 self.wheel_position_old_ready = False 00042 self.msg_fuel_level = FuelLevelReport() 00043 self.msg_fuel_level_ready = False 00044 self.msg_wheel_position = WheelPositionReport() 00045 self.msg_wheel_position_ready = False 00046 00047 # Subscribers 00048 rospy.Subscriber('/vehicle/fuel_level_report', FuelLevelReport, self.recv_fuel_level) 00049 rospy.Subscriber('/vehicle/wheel_position_report', WheelPositionReport, self.recv_wheel_position) 00050 00051 def recv_fuel_level(self, msg): 00052 if self.msg_fuel_level_ready: 00053 if int(msg.odometer) == int(self.msg_fuel_level.odometer + 1): 00054 if self.wheel_position_old_ready: 00055 diff = self.msg_wheel_position.rear_left - self.wheel_position_old.rear_left 00056 if diff < 0: 00057 diff += 65536 00058 rospy.loginfo('Odometer km increment: ' + str(diff) + ' wheel position counts.') 00059 else: 00060 rospy.loginfo('Odometer km increment: (first)') 00061 if self.msg_wheel_position_ready: 00062 self.wheel_position_old = self.msg_wheel_position 00063 self.wheel_position_old_ready = True 00064 self.msg_fuel_level = msg 00065 self.msg_fuel_level_ready = True 00066 00067 def recv_wheel_position(self, msg): 00068 self.msg_wheel_position = msg 00069 self.msg_wheel_position_ready = True 00070 00071 if __name__ == '__main__': 00072 try: 00073 node = WheelCountsPerKm() 00074 rospy.spin() 00075 except rospy.ROSInterruptException: 00076 pass 00077