wheel_counts_per_km.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 # Software License Agreement (BSD License)
4 #
5 # Copyright (c) 2019, Dataspeed Inc.
6 # All rights reserved.
7 #
8 # Redistribution and use in source and binary forms, with or without modification,
9 # are permitted provided that the following conditions are met:
10 #
11 # * Redistributions of source code must retain the above copyright notice,
12 # this list of conditions and the following disclaimer.
13 # * Redistributions in binary form must reproduce the above copyright notice,
14 # this list of conditions and the following disclaimer in the documentation
15 # and/or other materials provided with the distribution.
16 # * Neither the name of Dataspeed Inc. nor the names of its
17 # contributors may be used to endorse or promote products derived from this
18 # software without specific prior written permission.
19 #
20 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
21 # ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
22 # WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
23 # DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
24 # FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
25 # DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
26 # SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
27 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
28 # OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
29 # OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
30 
31 import rospy
32 from dbw_mkz_msgs.msg import WheelPositionReport, FuelLevelReport
33 from math import fabs
34 
36  def __init__(self):
37  rospy.init_node('wheel_counts_per_km')
38 
39  # Variables
42  self.msg_fuel_level = FuelLevelReport()
43  self.msg_fuel_level_ready = False
44  self.msg_wheel_position = WheelPositionReport()
46 
47  # Subscribers
48  rospy.Subscriber('/vehicle/fuel_level_report', FuelLevelReport, self.recv_fuel_level)
49  rospy.Subscriber('/vehicle/wheel_position_report', WheelPositionReport, self.recv_wheel_position)
50 
51  def recv_fuel_level(self, msg):
52  if self.msg_fuel_level_ready:
53  if int(msg.odometer) == int(self.msg_fuel_level.odometer + 1):
55  diff = self.msg_wheel_position.rear_left - self.wheel_position_old.rear_left
56  if diff < 0:
57  diff += 65536
58  rospy.loginfo('Odometer km increment: ' + str(diff) + ' wheel position counts.')
59  else:
60  rospy.loginfo('Odometer km increment: (first)')
63  self.wheel_position_old_ready = True
64  self.msg_fuel_level = msg
65  self.msg_fuel_level_ready = True
66 
67  def recv_wheel_position(self, msg):
68  self.msg_wheel_position = msg
69  self.msg_wheel_position_ready = True
70 
71 if __name__ == '__main__':
72  try:
74  rospy.spin()
75  except rospy.ROSInterruptException:
76  pass
77 


dbw_mkz_can
Author(s): Kevin Hallenbeck
autogenerated on Fri May 14 2021 02:47:08