32 from dbw_mkz_msgs.msg
import WheelPositionReport, FuelLevelReport
37 rospy.init_node(
'wheel_counts_per_km')
48 rospy.Subscriber(
'/vehicle/fuel_level_report', FuelLevelReport, self.
recv_fuel_level)
49 rospy.Subscriber(
'/vehicle/wheel_position_report', WheelPositionReport, self.
recv_wheel_position)
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
58 rospy.loginfo(
'Odometer km increment: ' + str(diff) +
' wheel position counts.')
60 rospy.loginfo(
'Odometer km increment: (first)')
71 if __name__ ==
'__main__':
75 except rospy.ROSInterruptException:
def recv_fuel_level(self, msg)
def recv_wheel_position(self, msg)