speed_filter.cc
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2009, Ingo Kresse <kresse@in.tum.de>
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 
32 
33 void SpeedFilter::input_vel(const geometry_msgs::Twist::ConstPtr& msg)
34 {
35  geometry_msgs::Twist t = *msg;
36 
37  dist_control_.compute_distance_keeping(&(t.linear.x), &(t.linear.y), &(t.angular.z));
38  pub_vel_.publish(t);
39 }
40 
41 
43 {
44  sub_vel_ = n_.subscribe("/input_vel", 1, &SpeedFilter::input_vel, this);
45  pub_vel_ = n_.advertise<geometry_msgs::Twist>("/cmd_vel", 1);
46 
47  //CHANGED
48  // dist_control_.setFootprint(0.42, -0.3075, 0.3075, -0.42, 0.0);
49  double front, rear, left, right, tolerance;
50  n_.param("footprint/left", left, 0.309);
51  n_.param("footprint/right", right, -0.309);
52  n_.param("footprint/front", front, 0.43);
53  n_.param("footprint/rear", rear, -0.43);
54  n_.param("footprint/tolerance", tolerance, 0.0);
55  dist_control_.setFootprint(front, rear, left, right, tolerance);
56 }
57 
58 int main(int argc, char *argv[])
59 {
60  ros::init(argc, argv, "speed_filter");
61 
62  SpeedFilter sf;
63 
64  ros::spin();
65 
66  return 0;
67 }
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
BaseDistance dist_control_
Definition: speed_filter.h:40
void input_vel(const geometry_msgs::Twist::ConstPtr &msg)
Definition: speed_filter.cc:33
void setFootprint(double front, double rear, double left, double right, double tolerance)
Sets front_, rear_, left_, right_, tolerance_, and early_reject_distance_.
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL void spin(Spinner &spinner)
ros::Subscriber sub_vel_
Definition: speed_filter.h:44
bool param(const std::string &param_name, T &param_val, const T &default_val) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
int main(int argc, char *argv[])
Definition: speed_filter.cc:58
void compute_distance_keeping(double *vx, double *vy, double *vth)
Sets vx_last_, vy_last and vth_last_ to input parameters, adjusting them.
ros::NodeHandle n_
Definition: speed_filter.h:42
ros::Publisher pub_vel_
Definition: speed_filter.h:43


nav_pcontroller
Author(s): Ingo Kresse
autogenerated on Thu Jun 6 2019 19:20:56