speed_filter.cc
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2009, Ingo Kresse <kresse@in.tum.de>
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 
00031 #include "nav_pcontroller/speed_filter.h"
00032 
00033 void SpeedFilter::input_vel(const geometry_msgs::Twist::ConstPtr& msg)
00034 {
00035   geometry_msgs::Twist t = *msg;
00036 
00037   dist_control_.compute_distance_keeping(&(t.linear.x), &(t.linear.y), &(t.angular.z));
00038   pub_vel_.publish(t);
00039 }
00040 
00041 
00042 SpeedFilter::SpeedFilter() : n_("~")
00043 {
00044   sub_vel_ =  n_.subscribe("/input_vel", 1, &SpeedFilter::input_vel, this);
00045   pub_vel_ =  n_.advertise<geometry_msgs::Twist>("/cmd_vel", 1);
00046 
00047   //CHANGED
00048   //  dist_control_.setFootprint(0.42, -0.3075, 0.3075, -0.42, 0.0);
00049   double front, rear, left, right, tolerance;
00050   n_.param("footprint/left", left, 0.309);
00051   n_.param("footprint/right", right, -0.309);
00052   n_.param("footprint/front", front, 0.43);
00053   n_.param("footprint/rear", rear, -0.43);
00054   n_.param("footprint/tolerance", tolerance, 0.0);
00055   dist_control_.setFootprint(front, rear, left, right, tolerance);
00056 }
00057 
00058 int main(int argc, char *argv[])
00059 {
00060   ros::init(argc, argv, "speed_filter");
00061 
00062   SpeedFilter sf;
00063 
00064   ros::spin();
00065 
00066   return 0;
00067 }


nav_pcontroller
Author(s): Ingo Kresse
autogenerated on Thu Jun 6 2019 20:28:18