Main Page
Related Pages
Namespaces
Classes
Files
File List
File Members
include
nav_pcontroller
speed_filter.h
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
#ifndef SPEED_FILTER_H
31
#define SPEED_FILTER_H
32
33
#include "
ros/ros.h
"
34
#include <geometry_msgs/Twist.h>
35
36
#include "
BaseDistance.h
"
37
38
class
SpeedFilter
{
39
private
:
40
BaseDistance
dist_control_
;
41
42
ros::NodeHandle
n_
;
43
ros::Publisher
pub_vel_
;
44
ros::Subscriber
sub_vel_
;
45
46
void
input_vel
(
const
geometry_msgs::Twist::ConstPtr& msg);
47
48
public
:
49
SpeedFilter
();
50
};
51
52
#endif
ros::NodeHandle
SpeedFilter
Definition:
speed_filter.h:38
SpeedFilter::dist_control_
BaseDistance dist_control_
Definition:
speed_filter.h:40
SpeedFilter::input_vel
void input_vel(const geometry_msgs::Twist::ConstPtr &msg)
Definition:
speed_filter.cc:33
SpeedFilter::sub_vel_
ros::Subscriber sub_vel_
Definition:
speed_filter.h:44
SpeedFilter::SpeedFilter
SpeedFilter()
Definition:
speed_filter.cc:42
ros::Subscriber
ros.h
SpeedFilter::n_
ros::NodeHandle n_
Definition:
speed_filter.h:42
SpeedFilter::pub_vel_
ros::Publisher pub_vel_
Definition:
speed_filter.h:43
BaseDistance.h
ros::Publisher
BaseDistance
Definition:
BaseDistance.h:80
nav_pcontroller
Author(s): Ingo Kresse
autogenerated on Thu Jun 6 2019 19:20:56