Go to the documentation of this file.00001
00009
00010
00011
00012
00013 #include <ros/ros.h>
00014 #include <nodelet/nodelet.h>
00015 #include <pluginlib/class_list_macros.h>
00016
00017 #include <dynamic_reconfigure/server.h>
00018 #include <yocs_velocity_smoother/paramsConfig.h>
00019
00020 #include <ecl/threads/thread.hpp>
00021
00022 #include "../include/velocity_smoother/velocity_smoother_nodelet.hpp"
00023
00024
00025
00026
00027
00028 #define PERIOD_RECORD_SIZE 5
00029 #define ZERO_VEL_COMMAND geometry_msgs::Twist();
00030 #define IS_ZERO_VEOCITY(a) ((a.linear.x == 0.0) && (a.angular.z == 0.0))
00031
00032
00033
00034
00035
00036 namespace yocs_velocity_smoother {
00037
00038
00039
00040
00041
00042 void VelocitySmoother::reconfigCB(yocs_velocity_smoother::paramsConfig &config, uint32_t level)
00043 {
00044 ROS_INFO("Reconfigure request : %f %f %f %f %f",
00045 config.speed_lim_v, config.speed_lim_w, config.accel_lim_v, config.accel_lim_w, config.decel_factor);
00046
00047 speed_lim_v = config.speed_lim_v;
00048 speed_lim_w = config.speed_lim_w;
00049 accel_lim_v = config.accel_lim_v;
00050 accel_lim_w = config.accel_lim_w;
00051 decel_factor = config.decel_factor;
00052 decel_lim_v = decel_factor*accel_lim_v;
00053 decel_lim_w = decel_factor*accel_lim_w;
00054 }
00055
00056 void VelocitySmoother::velocityCB(const geometry_msgs::Twist::ConstPtr& msg)
00057 {
00058
00059
00060 if (period_record.size() < PERIOD_RECORD_SIZE)
00061 {
00062 period_record.push_back((ros::Time::now() - last_cb_time).toSec());
00063 }
00064 else
00065 {
00066 period_record[pr_next] = (ros::Time::now() - last_cb_time).toSec();
00067 }
00068
00069 pr_next++;
00070 pr_next %= period_record.size();
00071 last_cb_time = ros::Time::now();
00072
00073 if (period_record.size() <= PERIOD_RECORD_SIZE/2)
00074 {
00075
00076 cb_avg_time = 0.05;
00077 }
00078 else
00079 {
00080
00081 cb_avg_time = median(period_record);
00082 }
00083
00084 input_active = true;
00085
00086
00087 target_vel.linear.x =
00088 msg->linear.x > 0.0 ? std::min(msg->linear.x, speed_lim_v) : std::max(msg->linear.x, -speed_lim_v);
00089 target_vel.angular.z =
00090 msg->angular.z > 0.0 ? std::min(msg->angular.z, speed_lim_w) : std::max(msg->angular.z, -speed_lim_w);
00091 }
00092
00093 void VelocitySmoother::odometryCB(const nav_msgs::Odometry::ConstPtr& msg)
00094 {
00095 odometry_vel = msg->twist.twist;
00096 }
00097
00098 void VelocitySmoother::spin()
00099 {
00100 double period = 1.0/frequency;
00101 ros::Rate spin_rate(frequency);
00102
00103 while (! shutdown_req && ros::ok())
00104 {
00105 if ((input_active == true) &&
00106 ((ros::Time::now() - last_cb_time).toSec() > std::min(3.0*cb_avg_time, 0.5)))
00107 {
00108
00109
00110
00111 input_active = false;
00112 if (IS_ZERO_VEOCITY(target_vel) == false)
00113 {
00114 ROS_WARN_STREAM("Velocity Smoother : input got inactive leaving us a non-zero target velocity ("
00115 << target_vel.linear.x << ", " << target_vel.angular.z << "), zeroing...[" << name << "]");
00116 target_vel = ZERO_VEL_COMMAND;
00117 }
00118 }
00119
00120 if ((input_active == true) &&
00121 (((ros::Time::now() - last_cb_time).toSec() > 5.0*cb_avg_time) ||
00122 (std::abs(odometry_vel.linear.x - last_cmd_vel.linear.x) > 0.2) ||
00123 (std::abs(odometry_vel.angular.z - last_cmd_vel.angular.z) > 2.0)))
00124 {
00125
00126
00127
00128
00129
00130 ROS_WARN("Using odometry instead of last command: %f, %f, %f",
00131 (ros::Time::now() - last_cb_time).toSec(),
00132 odometry_vel.linear.x - last_cmd_vel.linear.x,
00133 odometry_vel.angular.z - last_cmd_vel.angular.z);
00134 last_cmd_vel = odometry_vel;
00135 }
00136
00137 geometry_msgs::TwistPtr cmd_vel;
00138
00139 if ((target_vel.linear.x != last_cmd_vel.linear.x) ||
00140 (target_vel.angular.z != last_cmd_vel.angular.z))
00141 {
00142
00143 cmd_vel.reset(new geometry_msgs::Twist(target_vel));
00144
00145 double v_inc, w_inc, max_v_inc, max_w_inc;
00146
00147 v_inc = target_vel.linear.x - last_cmd_vel.linear.x;
00148 if (odometry_vel.linear.x*target_vel.linear.x < 0.0)
00149 {
00150 max_v_inc = decel_lim_v*period;
00151 }
00152 else
00153 {
00154 max_v_inc = ((v_inc*target_vel.linear.x > 0.0)?accel_lim_v:decel_lim_v)*period;
00155 }
00156
00157 w_inc = target_vel.angular.z - last_cmd_vel.angular.z;
00158 if (odometry_vel.angular.z*target_vel.angular.z < 0.0)
00159 {
00160 max_w_inc = decel_lim_w*period;
00161 }
00162 else
00163 {
00164 max_w_inc = ((w_inc*target_vel.angular.z > 0.0)?accel_lim_w:decel_lim_w)*period;
00165 }
00166
00167
00168
00169
00170 double MA = sqrt( v_inc * v_inc + w_inc * w_inc);
00171 double MB = sqrt(max_v_inc * max_v_inc + max_w_inc * max_w_inc);
00172
00173 double Av = std::abs(v_inc) / MA;
00174 double Aw = std::abs(w_inc) / MA;
00175 double Bv = max_v_inc / MB;
00176 double Bw = max_w_inc / MB;
00177 double theta = atan2(Bw, Bv) - atan2(Aw, Av);
00178
00179 if (theta < 0)
00180 {
00181
00182 max_v_inc = (max_w_inc*std::abs(v_inc))/std::abs(w_inc);
00183 }
00184 else
00185 {
00186
00187 max_w_inc = (max_v_inc*std::abs(w_inc))/std::abs(v_inc);
00188 }
00189
00190 if (std::abs(v_inc) > max_v_inc)
00191 {
00192
00193 cmd_vel->linear.x = last_cmd_vel.linear.x + sign(v_inc)*max_v_inc;
00194 }
00195
00196 if (std::abs(w_inc) > max_w_inc)
00197 {
00198
00199 cmd_vel->angular.z = last_cmd_vel.angular.z + sign(w_inc)*max_w_inc;
00200 }
00201
00202 lim_vel_pub.publish(cmd_vel);
00203 last_cmd_vel = *cmd_vel;
00204 }
00205 else if (input_active == true)
00206 {
00207
00208 cmd_vel.reset(new geometry_msgs::Twist(last_cmd_vel));
00209 lim_vel_pub.publish(cmd_vel);
00210 }
00211
00212 spin_rate.sleep();
00213 }
00214 }
00215
00221 bool VelocitySmoother::init(ros::NodeHandle& nh)
00222 {
00223
00224 dynamic_reconfigure_callback = boost::bind(&VelocitySmoother::reconfigCB, this, _1, _2);
00225
00226 dynamic_reconfigure_server = new dynamic_reconfigure::Server<yocs_velocity_smoother::paramsConfig>(nh);
00227 dynamic_reconfigure_server->setCallback(dynamic_reconfigure_callback);
00228
00229
00230 nh.param("frequency", frequency, 20.0);
00231 nh.param("decel_factor", decel_factor, 1.0);
00232
00233
00234 if ((nh.getParam("speed_lim_v", speed_lim_v) == false) ||
00235 (nh.getParam("speed_lim_w", speed_lim_w) == false))
00236 {
00237 ROS_ERROR("Missing velocity limit parameter(s)");
00238 return false;
00239 }
00240
00241 if ((nh.getParam("accel_lim_v", accel_lim_v) == false) ||
00242 (nh.getParam("accel_lim_w", accel_lim_w) == false))
00243 {
00244 ROS_ERROR("Missing acceleration limit parameter(s)");
00245 return false;
00246 }
00247
00248
00249 decel_lim_v = decel_factor*accel_lim_v;
00250 decel_lim_w = decel_factor*accel_lim_w;
00251
00252
00253 cur_vel_sub = nh.subscribe("odometry", 1, &VelocitySmoother::odometryCB, this);
00254 raw_vel_sub = nh.subscribe("raw_cmd_vel", 1, &VelocitySmoother::velocityCB, this);
00255 lim_vel_pub = nh.advertise <geometry_msgs::Twist> ("smooth_cmd_vel", 1);
00256
00257 return true;
00258 }
00259
00260
00261
00262
00263
00264
00265 class VelocitySmootherNodelet : public nodelet::Nodelet
00266 {
00267 public:
00268 VelocitySmootherNodelet() { }
00269 ~VelocitySmootherNodelet()
00270 {
00271 NODELET_DEBUG("Velocity Smoother : waiting for worker thread to finish...");
00272 vel_smoother_->shutdown();
00273 worker_thread_.join();
00274 }
00275
00276 std::string unresolvedName(const std::string &name) const {
00277 size_t pos = name.find_last_of('/');
00278 return name.substr(pos + 1);
00279 }
00280
00281
00282 virtual void onInit()
00283 {
00284 ros::NodeHandle ph = getPrivateNodeHandle();
00285 std::string resolved_name = ph.getUnresolvedNamespace();
00286 std::string name = unresolvedName(resolved_name);
00287 NODELET_DEBUG_STREAM("Velocity Smoother : initialising nodelet...[" << name << "]");
00288 vel_smoother_.reset(new VelocitySmoother(name));
00289 if (vel_smoother_->init(ph))
00290 {
00291 NODELET_DEBUG_STREAM("Velocity Smoother : nodelet initialised [" << name << "]");
00292 worker_thread_.start(&VelocitySmoother::spin, *vel_smoother_);
00293 }
00294 else
00295 {
00296 NODELET_ERROR_STREAM("Velocity Smoother : nodelet initialisation failed [" << name << "]");
00297 }
00298 }
00299
00300 private:
00301 boost::shared_ptr<VelocitySmoother> vel_smoother_;
00302 ecl::Thread worker_thread_;
00303 };
00304
00305 }
00306
00307 PLUGINLIB_EXPORT_CLASS(yocs_velocity_smoother::VelocitySmootherNodelet, nodelet::Nodelet);