velocity_smoother.h
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9 
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 
18 #ifndef VELOCITY_SMOOTHER_HPP_
19 #define VELOCITY_SMOOTHER_HPP_
20 
21 /*****************************************************************************
22  ** Includes
23  *****************************************************************************/
24 
25 #include <ros/ros.h>
26 #include <dynamic_reconfigure/server.h>
27 #include <cob_base_velocity_smoother/paramsConfig.h>
28 #include <nav_msgs/Odometry.h>
29 
30 /*****************************************************************************
31 ** Namespaces
32 *****************************************************************************/
33 
35 
36 /*****************************************************************************
37 ** VelocitySmoother
38 *****************************************************************************/
39 
40 class VelocitySmoother
41 {
42 public:
43  VelocitySmoother(const std::string &name);
44 
46  {
47  if (dynamic_reconfigure_server != NULL)
49  }
50 
51  bool init(ros::NodeHandle& nh);
52  void spin();
53  void shutdown() { shutdown_req = true; };
54 
55 private:
57  {
58  NONE,
59  ODOMETRY,
60  COMMANDS
61  } robot_feedback;
63  std::string name;
68 
69  double frequency;
70 
71  geometry_msgs::Twist last_cmd_vel;
72  geometry_msgs::Twist current_vel;
73  geometry_msgs::Twist target_vel;
74 
75  bool shutdown_req;
77  double cb_avg_time;
79  std::vector<double> period_record;
80  unsigned int pr_next;
87  void velocityCB(const geometry_msgs::Twist::ConstPtr& msg);
88  void robotVelCB(const geometry_msgs::Twist::ConstPtr& msg);
89  void odometryCB(const nav_msgs::Odometry::ConstPtr& msg);
90 
91  double sign(double x) { return x < 0.0 ? -1.0 : +1.0; };
92 
93  double median(std::vector<double> values) {
94  // Return the median element of an doubles vector
95  nth_element(values.begin(), values.begin() + values.size()/2, values.end());
96  return values[values.size()/2];
97  };
98 
99  /*********************
100  ** Dynamic Reconfigure
101  **********************/
102  dynamic_reconfigure::Server<cob_base_velocity_smoother::paramsConfig> * dynamic_reconfigure_server;
103  dynamic_reconfigure::Server<cob_base_velocity_smoother::paramsConfig>::CallbackType dynamic_reconfigure_callback;
104  void reconfigCB(cob_base_velocity_smoother::paramsConfig &config, uint32_t unused_level);
105 };
106 
107 } // cob_base_velocity_smoother
108 
109 #endif /* VELOCITY_SMOOTHER_HPP_ */
cob_base_velocity_smoother::VelocitySmoother::dynamic_reconfigure_callback
dynamic_reconfigure::Server< cob_base_velocity_smoother::paramsConfig >::CallbackType dynamic_reconfigure_callback
Definition: velocity_smoother.h:113
cob_base_velocity_smoother::VelocitySmoother::NONE
@ NONE
Definition: velocity_smoother.h:68
cob_base_velocity_smoother::VelocitySmoother::speed_lim_vy
double speed_lim_vy
Definition: velocity_smoother.h:75
ros::Publisher
cob_base_velocity_smoother::VelocitySmoother::median
double median(std::vector< double > values)
Definition: velocity_smoother.h:103
cob_base_velocity_smoother::VelocitySmoother::robotVelCB
void robotVelCB(const geometry_msgs::Twist::ConstPtr &msg)
Definition: velocity_smoother.cpp:125
cob_base_velocity_smoother::VelocitySmoother::name
std::string name
Definition: velocity_smoother.h:73
cob_base_velocity_smoother::VelocitySmoother::decel_factor
double decel_factor
Definition: velocity_smoother.h:77
ros.h
cob_base_velocity_smoother::VelocitySmoother::sign
double sign(double x)
Definition: velocity_smoother.h:101
cob_base_velocity_smoother::VelocitySmoother::decel_lim_vy
double decel_lim_vy
Definition: velocity_smoother.h:75
cob_base_velocity_smoother::VelocitySmoother::current_vel_sub
ros::Subscriber current_vel_sub
Definition: velocity_smoother.h:93
cob_base_velocity_smoother::VelocitySmoother::VelocitySmoother
VelocitySmoother(const std::string &name)
Definition: velocity_smoother.cpp:48
cob_base_velocity_smoother::VelocitySmoother::shutdown
void shutdown()
Definition: velocity_smoother.h:63
cob_base_velocity_smoother::VelocitySmoother::decel_lim_vx
double decel_lim_vx
Definition: velocity_smoother.h:74
cob_base_velocity_smoother::VelocitySmoother::last_cb_time
ros::Time last_cb_time
Definition: velocity_smoother.h:88
cob_base_velocity_smoother::VelocitySmoother::accel_lim_vy
double accel_lim_vy
Definition: velocity_smoother.h:75
cob_base_velocity_smoother::VelocitySmoother::dynamic_reconfigure_server
dynamic_reconfigure::Server< cob_base_velocity_smoother::paramsConfig > * dynamic_reconfigure_server
Definition: velocity_smoother.h:107
cob_base_velocity_smoother::VelocitySmoother::shutdown_req
bool shutdown_req
Definition: velocity_smoother.h:85
cob_base_velocity_smoother::VelocitySmoother::odometryCB
void odometryCB(const nav_msgs::Odometry::ConstPtr &msg)
Definition: velocity_smoother.cpp:117
cob_base_velocity_smoother::VelocitySmoother::decel_lim_w
double decel_lim_w
Definition: velocity_smoother.h:76
cob_base_velocity_smoother::VelocitySmoother::odometry_sub
ros::Subscriber odometry_sub
Definition: velocity_smoother.h:92
cob_base_velocity_smoother::VelocitySmoother::speed_lim_w
double speed_lim_w
Definition: velocity_smoother.h:76
cob_base_velocity_smoother::VelocitySmoother::RobotFeedbackType
RobotFeedbackType
Definition: velocity_smoother.h:66
cob_base_velocity_smoother::VelocitySmoother::current_vel
geometry_msgs::Twist current_vel
Definition: velocity_smoother.h:82
cob_base_velocity_smoother::VelocitySmoother::accel_lim_vx
double accel_lim_vx
Definition: velocity_smoother.h:74
cob_base_velocity_smoother::VelocitySmoother::decel_lim_vx_safe
double decel_lim_vx_safe
Definition: velocity_smoother.h:74
cob_base_velocity_smoother::VelocitySmoother::cb_avg_time
double cb_avg_time
Definition: velocity_smoother.h:87
cob_base_velocity_smoother::VelocitySmoother::COMMANDS
@ COMMANDS
Definition: velocity_smoother.h:70
cob_base_velocity_smoother::VelocitySmoother::~VelocitySmoother
~VelocitySmoother()
Definition: velocity_smoother.h:55
cob_base_velocity_smoother::VelocitySmoother::period_record
std::vector< double > period_record
Definition: velocity_smoother.h:89
cob_base_velocity_smoother::VelocitySmoother::velocityCB
void velocityCB(const geometry_msgs::Twist::ConstPtr &msg)
Definition: velocity_smoother.cpp:78
cob_base_velocity_smoother::VelocitySmoother::input_active
bool input_active
Definition: velocity_smoother.h:86
cob_base_velocity_smoother::VelocitySmoother::target_vel
geometry_msgs::Twist target_vel
Definition: velocity_smoother.h:83
cob_base_velocity_smoother::VelocitySmoother::spin
void spin()
Definition: velocity_smoother.cpp:133
ros::Time
cob_base_velocity_smoother::VelocitySmoother::raw_in_vel_sub
ros::Subscriber raw_in_vel_sub
Definition: velocity_smoother.h:94
cob_base_velocity_smoother::VelocitySmoother::ODOMETRY
@ ODOMETRY
Definition: velocity_smoother.h:69
cob_base_velocity_smoother::VelocitySmoother::reconfigCB
void reconfigCB(cob_base_velocity_smoother::paramsConfig &config, uint32_t unused_level)
Definition: velocity_smoother.cpp:57
cob_base_velocity_smoother::VelocitySmoother::speed_lim_vx
double speed_lim_vx
Definition: velocity_smoother.h:74
cob_base_velocity_smoother::VelocitySmoother::frequency
double frequency
Definition: velocity_smoother.h:79
cob_base_velocity_smoother::VelocitySmoother::accel_lim_w
double accel_lim_w
Definition: velocity_smoother.h:76
cob_base_velocity_smoother::VelocitySmoother::decel_factor_safe
double decel_factor_safe
Definition: velocity_smoother.h:77
cob_base_velocity_smoother
Definition: velocity_smoother.h:34
cob_base_velocity_smoother::VelocitySmoother::robot_feedback
enum cob_base_velocity_smoother::VelocitySmoother::RobotFeedbackType robot_feedback
cob_base_velocity_smoother::VelocitySmoother::init
bool init(ros::NodeHandle &nh)
Definition: velocity_smoother.cpp:302
cob_base_velocity_smoother::VelocitySmoother::decel_lim_vy_safe
double decel_lim_vy_safe
Definition: velocity_smoother.h:75
cob_base_velocity_smoother::VelocitySmoother::decel_lim_w_safe
double decel_lim_w_safe
Definition: velocity_smoother.h:76
cob_base_velocity_smoother::VelocitySmoother::last_cmd_vel
geometry_msgs::Twist last_cmd_vel
Definition: velocity_smoother.h:81
cob_base_velocity_smoother::VelocitySmoother::smooth_vel_pub
ros::Publisher smooth_vel_pub
Definition: velocity_smoother.h:95
cob_base_velocity_smoother::VelocitySmoother::pr_next
unsigned int pr_next
Definition: velocity_smoother.h:90
ros::NodeHandle
ros::Subscriber


cob_base_velocity_smoother
Author(s): Florian Mirus , Benjamin Maidel
autogenerated on Mon May 1 2023 02:44:18