wheel_velocity.py
Go to the documentation of this file.
00001 #! /usr/bin/env python
00002 # -*- coding: utf-8 -*-
00003 
00004 # Software License Agreement (BSD)
00005 #
00006 #  file      @wheel_velocity.py
00007 #  authors   Mike Purvis <mpurvis@clearpathrobotics.com>
00008 #            NovAtel <novatel.com/support>
00009 #  copyright Copyright (c) 2012, Clearpath Robotics, Inc., All rights reserved.
00010 #            Copyright (c) 2014, NovAtel Inc., All rights reserved.
00011 #
00012 # Redistribution and use in source and binary forms, with or without modification, are permitted provided that
00013 # the following conditions are met:
00014 #  * Redistributions of source code must retain the above copyright notice, this list of conditions and the
00015 #    following disclaimer.
00016 #  * Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the
00017 #    following disclaimer in the documentation and/or other materials provided with the distribution.
00018 #  * Neither the name of Clearpath Robotics nor the names of its contributors may be used to endorse or promote
00019 #    products derived from this software without specific prior written permission.
00020 #
00021 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WAR-
00022 # RANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
00023 # PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, IN-
00024 # DIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT
00025 # OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00026 # ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00027 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00028 
00029 import rospy
00030 from nav_msgs.msg import Odometry
00031 from math import pi
00032 
00033 
00034 class NovatelWheelVelocity(object):
00035     """ Subscribes to a platform's odom topic and sends SPAN
00036         wheelvelocity messages about the platform's linear movement. """
00037 
00038     def __init__(self, port):
00039         self.port = port
00040 
00041         # The Odometry message doesn't expose this information to us, so we
00042         # make up a fake wheel which is rotated and ticked based on how far
00043         # the odom topic tells us we traveled.
00044         self.fake_wheel_diameter = rospy.get_param("~fake_wheel/diameter", 0.33)
00045         self.fake_wheel_ticks = rospy.get_param("~fake_wheel/ticks", 1000)
00046 
00047         # SPAN wants to know how much delay is associated with our velocity report.
00048         # This is specified in milliseconds.
00049         self.latency = rospy.get_param("~wheel_velocity_latency", 100)
00050         max_frequency = rospy.get_param("~wheel_velocity_max_frequency", 1.0)
00051         self.minimum_period = rospy.Duration(1.0 / max_frequency)
00052 
00053         # Send setup command.
00054         self.circumference = self.fake_wheel_diameter * pi
00055         cmd = 'setwheelparameters %d %f %f' % (
00056             self.fake_wheel_ticks,
00057             self.circumference,
00058             self.circumference / self.fake_wheel_ticks)
00059 
00060         rospy.logdebug("Sending: %s" % cmd)
00061         self.port.send(cmd)
00062 
00063         self.cumulative_ticks = 0
00064         self.last_received_stamp = None
00065         self.last_sent = None
00066         rospy.Subscriber('odom', Odometry, self.odom_handler)
00067 
00068     def odom_handler(self, odom):
00069         if self.last_received_stamp:
00070             # Robot's linear velocity in m/s.
00071             velocity = abs(odom.twist.twist.linear.x)
00072             velocity_ticks = velocity * self.fake_wheel_ticks / self.circumference
00073 
00074             period = (odom.header.stamp - self.last_received_stamp).to_sec()
00075             self.cumulative_ticks += velocity_ticks * period
00076 
00077             cmd = 'wheelvelocity %d %d %d 0 %f 0 0 %d \r\n' % (
00078                 self.latency,
00079                 self.fake_wheel_ticks,
00080                 int(velocity_ticks),
00081                 velocity_ticks,
00082                 self.cumulative_ticks)
00083 
00084             if not self.last_sent or (odom.header.stamp - self.last_sent) > self.minimum_period:
00085                 rospy.logdebug("Sending: %s" % repr(cmd))
00086                 self.port.send(cmd)
00087                 self.last_sent = odom.header.stamp
00088 
00089         self.last_received_stamp = odom.header.stamp


novatel_span_driver
Author(s): NovAtel Support
autogenerated on Thu Sep 28 2017 03:12:25