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 
00061 #include <unistd.h>
00062 #include <math.h>
00063 
00064 #include "ros/ros.h"
00065 
00066 
00067 #include "tf/transform_listener.h"
00068 
00069 
00070 // The messages that we'll use
00071 //#include <nav_robot_actions/MoveBaseState.h>
00072 #include <geometry_msgs/PoseStamped.h>
00073 #include <geometry_msgs/Twist.h>
00074 #include <std_msgs/String.h>
00075 
00076 #include <sensor_msgs/LaserScan.h>
00077 
00078 #include "BaseDistance.h"
00079 
00080 class SpeedFilter {
00081 private:
00082   BaseDistance dist_control_;
00083 
00084   ros::NodeHandle n_;
00085   ros::Publisher  pub_vel_;
00086   ros::Subscriber sub_vel_;
00087 
00088   void input_vel(const geometry_msgs::Twist::ConstPtr& msg);
00089   
00090 public:
00091   SpeedFilter();
00092 };
00093 
00094 void SpeedFilter::input_vel(const geometry_msgs::Twist::ConstPtr& msg)
00095 {
00096   geometry_msgs::Twist t = *msg;
00097 
00098   dist_control_.compute_distance_keeping(&(t.linear.x), &(t.linear.y), &(t.angular.z));
00099   pub_vel_.publish(t);
00100 }
00101 
00102 
00103 SpeedFilter::SpeedFilter() : n_("~")
00104 {
00105   sub_vel_ =  n_.subscribe("/input_vel", 1, &SpeedFilter::input_vel, this);
00106   pub_vel_ =  n_.advertise<geometry_msgs::Twist>("/cmd_vel", 1);
00107 
00108   //CHANGED
00109   //  dist_control_.setFootprint(0.42, -0.3075, 0.3075, -0.42, 0.0);
00110   double front, rear, left, right, tolerance;
00111   n_.param("footprint/left", left, 0.309);
00112   n_.param("footprint/right", right, -0.309);
00113   n_.param("footprint/front", front, 0.43);
00114   n_.param("footprint/rear", rear, -0.43);
00115   n_.param("footprint/tolerance", tolerance, 0.0);
00116   dist_control_.setFootprint(front, rear, left, right, tolerance);
00117 }
00118 
00119 int main(int argc, char *argv[])
00120 {
00121   ros::init(argc, argv, "speed_filter");
00122 
00123   SpeedFilter sf;
00124 
00125   ros::spin();
00126 
00127   return 0;
00128 }


nav_pcontroller
Author(s): Ingo Kresse
autogenerated on Mon Oct 6 2014 08:08:16