49 m_mutex = PTHREAD_MUTEX_INITIALIZER;
65 ROS_WARN(
"No parameter circular_buffer_capacity on parameter server. Using default [12]");
71 ROS_WARN(
"No parameter maximal_time_delay on parameter server. Using default [4 in s]");
77 ROS_WARN(
"No parameter maximal_time_delay_to_stop on parameter server. Using default [0.1 in s]");
83 ROS_WARN(
"No parameter thresh_max_acc on parameter server. Using default [0.3 in m/s]");
89 ROS_WARN(
"No parameter loop_rate on parameter server. Using default [30 in Hz]");
93 double min_input_rate;
96 ROS_WARN(
"No parameter min_input_rate on parameter server. Using default [9 in Hz]");
98 pnh_.
param(
"min_input_rate", min_input_rate, 9.0);
102 ROS_WARN(
"min_input_rate > loop_rate: Setting min_input_rate to loop_rate = %f",
loop_rate_);
125 while(
cb_.full() ==
false)
149 geometry_msgs::Twist result = geometry_msgs::Twist();
165 result = this->
setOutput(now, geometry_msgs::Twist());
211 while(
cb_.full() ==
false)
218 cb_.push_front(cmd_vel);
236 if(
cb_.empty() ==
true)
238 while(
cb_.full() ==
false)
247 long unsigned int size = floor(
cb_.size() / 3 );
250 for(
long unsigned int i=0; i< size; i++)
253 cb_.push_front(cmd_vel);
261 cb_.push_front(cmd_vel);
273 long unsigned int count=0;
275 while( (count <
cb_.size()) && (result ==
true) )
292 if( (cmd_vel.linear.x) != 0 || (cmd_vel.linear.y != 0) || (cmd_vel.angular.z != 0) )
316 long unsigned int size =
cb_.size();
319 for(
long unsigned int i=0; i<size; i++)
321 result +=
cb_[i].linear.x;
327 double help_result = 0;
328 double max =
cb_[0].linear.x;
329 long unsigned int max_ind = 0;
330 for(
long unsigned int i=0; i<size; i++)
332 if(abs(result-
cb_[i].linear.x) > abs(result-max))
334 max =
cb_[i].linear.x;
340 for(
long unsigned int i=0; i<size; i++)
344 help_result +=
cb_[i].linear.x;
347 result = help_result / (size - 1);
357 long unsigned int size =
cb_.size();
360 for(
long unsigned int i=0; i<size; i++)
362 result +=
cb_[i].linear.y;
368 double help_result = 0;
369 double max =
cb_[0].linear.y;
370 long unsigned int max_ind = 0;
371 for(
long unsigned int i=0; i<size; i++)
373 if(abs(result-
cb_[i].linear.y) > abs(result-max))
375 max =
cb_[i].linear.y;
381 for(
long unsigned int i=0; i<size; i++)
385 help_result +=
cb_[i].linear.y;
388 result = help_result / (size - 1);
398 long unsigned int size =
cb_.size();
401 for(
long unsigned int i=0; i<size; i++)
403 result +=
cb_[i].angular.z;
409 double help_result = 0;
410 double max =
cb_[0].angular.z;
411 long unsigned int max_ind = 0;
412 for(
long unsigned int i = 0; i < size; i++)
414 if(abs(result-
cb_[i].angular.z) > abs(result-max))
416 max =
cb_[i].angular.z;
422 for(
long unsigned int i = 0; i < size; i++)
426 help_result +=
cb_[i].angular.z;
429 result = help_result / (size - 1);
444 if( (msg1.linear.x == msg2.linear.x) && (msg1.linear.y == msg2.linear.y) && (msg1.angular.z == msg2.angular.z))
460 double deltaTime = 0;
472 double deltaX = result.linear.x -
cb_out_.front().linear.x;
474 double deltaY = result.linear.y -
cb_out_.front().linear.y;
476 double deltaZ = result.angular.z -
cb_out_.front().angular.z;
495 int main(
int argc,
char **argv)
498 ros::init(argc, argv,
"cob_base_velocity_smoother");
505 while(my_velocity_smoother.
nh_.
ok())
int main(int argc, char **argv)
void limitAcceleration(ros::Time now, geometry_msgs::Twist &cmd_vel)
double max_delay_between_commands_
geometry_msgs::Twist zero_values_
void publish(const boost::shared_ptr< M > &message) const
bool circBuffOutOfDate(ros::Time now)
geometry_msgs::Twist setOutput(ros::Time now, geometry_msgs::Twist cmd_vel)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::Subscriber geometry_msgs_sub_
void reviseCircBuff(ros::Time now, geometry_msgs::Twist cmd_vel)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool get_new_msg_received()
void set_new_msg_received(bool received)
bool IsEqual(geometry_msgs::Twist msg1, geometry_msgs::Twist msg2)
bool IsZeroMsg(geometry_msgs::Twist cmd_vel)
boost::circular_buffer< geometry_msgs::Twist > cb_out_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
cob_base_velocity_smoother()
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
boost::circular_buffer< geometry_msgs::Twist > cb_
geometry_msgs::Twist sub_msg_
~cob_base_velocity_smoother()
void geometryCallback(const geometry_msgs::Twist::ConstPtr &cmd_vel)
boost::circular_buffer< ros::Time > cb_time_
double stop_delay_after_no_sub_
bool hasParam(const std::string &key) const
ROSCPP_DECL void spinOnce()