uos_diffdrive_teleop.h
Go to the documentation of this file.
1 /*
2  *
3  * Copyright (C) 2015 University of Osnabrück, Germany
4  *
5  * This program is free software; you can redistribute it and/or
6  * modify it under the terms of the GNU General Public License
7  * as published by the Free Software Foundation; either version 2
8  * of the License, or (at your option) any later version.
9  *
10  * This program is distributed in the hope that it will be useful,
11  * but WITHOUT ANY WARRANTY; without even the implied warranty of
12  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13  * GNU General Public License for more details.
14  *
15  * You should have received a copy of the GNU General Public License
16  * along with this program; if not, write to the Free Software
17  * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA.
18  *
19  * uos_diffdrive_teleop.h
20  *
21  * Created on: 16.02.2015
22  * Author: Sebastian Pütz <spuetz@uos.de>
23  */
24 #ifndef UOS_DIFFDRIVE_TELEOP_H
25 #define UOS_DIFFDRIVE_TELEOP_H
26 
27 #include <ros/ros.h>
28 #include <geometry_msgs/Twist.h>
29 #include <algorithm>
30 
31 #define EPSILON_VELO 1e-3
32 
33 class Teleop
34 {
35  private:
39 
42 
43  void updateVelocity(const ros::TimerEvent &t_event);
44  void updateInputs(const ros::TimerEvent &t_event);
45 
46  double max_vel;
47  double max_rot_vel;
48 
49  geometry_msgs::Twist vel_cmd;
50 
51  struct acceleration{
52  double pos;
53  double neg;
54  double stop;
55  };
58 
59  struct velocity{
60  double x;
61  double y;
62  double dyn_limit_x;
63  double dyn_limit_y;
64  };
66 
67 
68  // inputs elem of [0 1]
69  struct inputs{
70  bool updated;
71  double forwards;
72  double left;
73  };
74 
75 
76  double adaptVelocity(
77  double time_delta,
78  double velocity,
79  double factor,
80  double acc_stop,
81  double acc_neg,
82  double acc_pos);
83 
84  protected:
87 
88  public:
89  Teleop();
90 };
91 
92 #endif /* uos_diffdrive_teleop.h */
double adaptVelocity(double time_delta, double velocity, double factor, double acc_stop, double acc_neg, double acc_pos)
double update_velocity_rate
void updateInputs(const ros::TimerEvent &t_event)
ros::Timer vel_timer
ros::NodeHandle n_
ros::Publisher vel_pub
ros::Timer key_timer
acceleration acc_x
double update_inputs_rate
geometry_msgs::Twist vel_cmd
velocity velo
void updateVelocity(const ros::TimerEvent &t_event)
acceleration acc_y
double max_rot_vel


uos_diffdrive_teleop
Author(s): Jochen Sprickerhof, Sebastian Pütz
autogenerated on Mon Jun 10 2019 15:49:27