cmd_vel_smoother.cpp
Go to the documentation of this file.
1 #include <cmath>
2 #include <boost/shared_ptr.hpp>
3 #include <ros/ros.h>
4 #include <dynamic_reconfigure/server.h>
5 #include <cmd_vel_smoother/CmdVelSmootherConfig.h>
6 #include <geometry_msgs/Twist.h>
7 
8 template<class T> inline T sgn(T val) { return val > 0 ? 1.0 : -1.0; }
9 
10 namespace dyn = dynamic_reconfigure;
11 
13 {
18 
19  boost::mutex cfg_mutex_;
20  typedef cmd_vel_smoother::CmdVelSmootherConfig Config;
22 
24  double desired_rate_;
27  geometry_msgs::Twist::ConstPtr latest_vel_;
28  geometry_msgs::Twist::Ptr pub_vel_;
29 
30 public:
32  return ros::Duration(1./(desired_rate_ * 2.2));
33  }
34 
35  void dynConfigCallback(Config &cfg, uint32_t level) {
36  boost::mutex::scoped_lock lock(cfg_mutex_);
37  x_acc_lim_ = cfg.x_acc_lim;
38  y_acc_lim_ = cfg.y_acc_lim;
39  yaw_acc_lim_ = cfg.yaw_acc_lim;
40  interpolate_max_frame_ = cfg.interpolate_max_frame;
41 
42  if(desired_rate_ != cfg.desired_rate) {
43  desired_rate_ = cfg.desired_rate;
44  if (timer_.isValid()) {
47  ROS_INFO_STREAM("timer loop rate is changed to " << 1.0 / d.toSec() << "[Hz]");
48  }
49  }
50  }
51 
52  void velCallback(const geometry_msgs::Twist::ConstPtr &msg){
54  latest_vel_ = msg;
55  count_ = 0;
56  pub_.publish(msg);
57  }
58 
59  void timerCallback(const ros::TimerEvent& event){
60  if (count_ > interpolate_max_frame_) return;
61  if (latest_vel_ == NULL) return;
62 
63  double past_sec = (event.current_real - latest_time_).toSec();
64  if (past_sec < 1.0 / desired_rate_) return;
65 
66  double g_x = std::abs(latest_vel_->linear.x / past_sec);
67  double g_y = std::abs(latest_vel_->linear.y / past_sec);
68  double g_yaw = std::abs(latest_vel_->angular.z / past_sec);
69 
70  ROS_DEBUG_STREAM("G: (" << g_x << ", " << g_y << ", " << g_yaw << ") detected");
71 
72  bool need_publish = false;
73  if (g_x > x_acc_lim_) {
74  pub_vel_->linear.x = (g_x - x_acc_lim_) * past_sec * sgn(latest_vel_->linear.x);
75  need_publish = true;
76  }
77 
78  if (g_y > y_acc_lim_) {
79  pub_vel_->linear.y = (g_y - y_acc_lim_) * past_sec * sgn(latest_vel_->linear.y);
80  need_publish = true;
81  }
82 
83  if (g_yaw > yaw_acc_lim_) {
84  pub_vel_->angular.z = (g_yaw - yaw_acc_lim_) * past_sec * sgn(latest_vel_->angular.z);
85  need_publish = true;
86  }
87 
88  if (need_publish)
90  count_++;
91  }
92 
95 
96  dyn_srv_ = boost::make_shared<dyn::Server<Config> >(pnh_);
97  dyn::Server<Config>::CallbackType f = boost::bind(&VelocitySmootherNode::dynConfigCallback, this, _1, _2);
98  dyn_srv_->setCallback(f);
99 
100  pub_vel_ = boost::shared_ptr<geometry_msgs::Twist>(new geometry_msgs::Twist());
101  pub_ = nh_.advertise<geometry_msgs::Twist>("output", 100);
102  sub_ = nh_.subscribe("input", 1, &VelocitySmootherNode::velCallback, this);
104  };
106 
107 };
108 
109 int main(int argc, char** argv) {
110  ros::init(argc, argv, "cmd_vel_smoother");
112  ros::spin();
113 
114  return 0;
115 }
116 
ros::Publisher
VelocitySmootherNode::dynConfigCallback
void dynConfigCallback(Config &cfg, uint32_t level)
Definition: cmd_vel_smoother.cpp:35
boost::shared_ptr
VelocitySmootherNode::count_
int count_
Definition: cmd_vel_smoother.cpp:23
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
VelocitySmootherNode::VelocitySmootherNode
VelocitySmootherNode()
Definition: cmd_vel_smoother.cpp:93
ros.h
VelocitySmootherNode::pnh_
ros::NodeHandle pnh_
Definition: cmd_vel_smoother.cpp:14
VelocitySmootherNode::dyn_srv_
boost::shared_ptr< dyn::Server< Config > > dyn_srv_
Definition: cmd_vel_smoother.cpp:21
main
int main(int argc, char **argv)
Definition: cmd_vel_smoother.cpp:109
ros::Timer::isValid
bool isValid()
VelocitySmootherNode::sub_
ros::Subscriber sub_
Definition: cmd_vel_smoother.cpp:16
VelocitySmootherNode::timer_
ros::Timer timer_
Definition: cmd_vel_smoother.cpp:17
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
VelocitySmootherNode::velCallback
void velCallback(const geometry_msgs::Twist::ConstPtr &msg)
Definition: cmd_vel_smoother.cpp:52
f
f
VelocitySmootherNode::latest_time_
ros::Time latest_time_
Definition: cmd_vel_smoother.cpp:26
VelocitySmootherNode::cfg_mutex_
boost::mutex cfg_mutex_
Definition: cmd_vel_smoother.cpp:19
VelocitySmootherNode::desired_rate_
double desired_rate_
Definition: cmd_vel_smoother.cpp:24
sgn
T sgn(T val)
Definition: cmd_vel_smoother.cpp:8
VelocitySmootherNode::timerCallback
void timerCallback(const ros::TimerEvent &event)
Definition: cmd_vel_smoother.cpp:59
VelocitySmootherNode::timerDuration
ros::Duration timerDuration()
Definition: cmd_vel_smoother.cpp:31
VelocitySmootherNode
Definition: cmd_vel_smoother.cpp:12
ros::Timer::setPeriod
void setPeriod(const Duration &period, bool reset=true)
VelocitySmootherNode::latest_vel_
geometry_msgs::Twist::ConstPtr latest_vel_
Definition: cmd_vel_smoother.cpp:27
d
d
VelocitySmootherNode::pub_vel_
geometry_msgs::Twist::Ptr pub_vel_
Definition: cmd_vel_smoother.cpp:28
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
ros::TimerEvent
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
VelocitySmootherNode::~VelocitySmootherNode
~VelocitySmootherNode()
Definition: cmd_vel_smoother.cpp:105
VelocitySmootherNode::y_acc_lim_
double y_acc_lim_
Definition: cmd_vel_smoother.cpp:25
VelocitySmootherNode::interpolate_max_frame_
int interpolate_max_frame_
Definition: cmd_vel_smoother.cpp:23
VelocitySmootherNode::nh_
ros::NodeHandle nh_
Definition: cmd_vel_smoother.cpp:14
ros::Time
VelocitySmootherNode::yaw_acc_lim_
double yaw_acc_lim_
Definition: cmd_vel_smoother.cpp:25
VelocitySmootherNode::pub_
ros::Publisher pub_
Definition: cmd_vel_smoother.cpp:15
ros::spin
ROSCPP_DECL void spin()
VelocitySmootherNode::Config
cmd_vel_smoother::CmdVelSmootherConfig Config
Definition: cmd_vel_smoother.cpp:20
VelocitySmootherNode::x_acc_lim_
double x_acc_lim_
Definition: cmd_vel_smoother.cpp:25
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
ros::Duration
ros::Timer
ros::NodeHandle
ros::Subscriber
ros::Time::now
static Time now()


cmd_vel_smoother
Author(s): Yuki Furuta
autogenerated on Mon Dec 9 2024 04:10:39