wheel_velocity.py
Go to the documentation of this file.
1 #! /usr/bin/env python
2 # -*- coding: utf-8 -*-
3 
4 # Software License Agreement (BSD)
5 #
6 # file @wheel_velocity.py
7 # authors Mike Purvis <mpurvis@clearpathrobotics.com>
8 # NovAtel <novatel.com/support>
9 # copyright Copyright (c) 2012, Clearpath Robotics, Inc., All rights reserved.
10 # Copyright (c) 2014, NovAtel Inc., All rights reserved.
11 #
12 # Redistribution and use in source and binary forms, with or without modification, are permitted provided that
13 # the following conditions are met:
14 # * Redistributions of source code must retain the above copyright notice, this list of conditions and the
15 # following disclaimer.
16 # * Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the
17 # following disclaimer in the documentation and/or other materials provided with the distribution.
18 # * Neither the name of Clearpath Robotics nor the names of its contributors may be used to endorse or promote
19 # products derived from this software without specific prior written permission.
20 #
21 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WAR-
22 # RANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
23 # PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, IN-
24 # DIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT
25 # OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
26 # ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 
29 import rospy
30 from nav_msgs.msg import Odometry
31 from math import pi
32 
33 
34 class NovatelWheelVelocity(object):
35  """ Subscribes to a platform's odom topic and sends SPAN
36  wheelvelocity messages about the platform's linear movement. """
37 
38  def __init__(self, port):
39  self.port = port
40 
41  # The Odometry message doesn't expose this information to us, so we
42  # make up a fake wheel which is rotated and ticked based on how far
43  # the odom topic tells us we traveled.
44  self.fake_wheel_diameter = rospy.get_param("~fake_wheel/diameter", 0.33)
45  self.fake_wheel_ticks = rospy.get_param("~fake_wheel/ticks", 1000)
46 
47  # SPAN wants to know how much delay is associated with our velocity report.
48  # This is specified in milliseconds.
49  self.latency = rospy.get_param("~wheel_velocity_latency", 100)
50  max_frequency = rospy.get_param("~wheel_velocity_max_frequency", 1.0)
51  self.minimum_period = rospy.Duration(1.0 / max_frequency)
52 
53  # Send setup command.
55  cmd = 'setwheelparameters %d %f %f' % (
56  self.fake_wheel_ticks,
57  self.circumference,
58  self.circumference / self.fake_wheel_ticks)
59 
60  rospy.logdebug("Sending: %s" % cmd)
61  self.port.send(cmd)
62 
64  self.last_received_stamp = None
65  self.last_sent = None
66  rospy.Subscriber('odom', Odometry, self.odom_handler)
67 
68  def odom_handler(self, odom):
69  if self.last_received_stamp:
70  # Robot's linear velocity in m/s.
71  velocity = abs(odom.twist.twist.linear.x)
72  velocity_ticks = velocity * self.fake_wheel_ticks / self.circumference
73 
74  period = (odom.header.stamp - self.last_received_stamp).to_sec()
75  self.cumulative_ticks += velocity_ticks * period
76 
77  cmd = 'wheelvelocity %d %d %d 0 %f 0 0 %d \r\n' % (
78  self.latency,
79  self.fake_wheel_ticks,
80  int(velocity_ticks),
81  velocity_ticks,
82  self.cumulative_ticks)
83 
84  if not self.last_sent or (odom.header.stamp - self.last_sent) > self.minimum_period:
85  rospy.logdebug("Sending: %s" % repr(cmd))
86  self.port.send(cmd)
87  self.last_sent = odom.header.stamp
88 
89  self.last_received_stamp = odom.header.stamp


novatel_span_driver
Author(s): NovAtel Support
autogenerated on Wed Apr 3 2019 02:52:53