Go to the documentation of this file.
    2 #include <boost/shared_ptr.hpp> 
    4 #include <dynamic_reconfigure/server.h> 
    5 #include <cmd_vel_smoother/CmdVelSmootherConfig.h> 
    6 #include <geometry_msgs/Twist.h> 
    8 template<
class T> 
inline T 
sgn(T val) { 
return val > 0 ? 1.0 : -1.0; }
 
   10 namespace dyn = dynamic_reconfigure;
 
   20   typedef cmd_vel_smoother::CmdVelSmootherConfig 
Config;
 
   47         ROS_INFO_STREAM(
"timer loop rate is changed to " << 1.0 / 
d.toSec() << 
"[Hz]");
 
   63     double past_sec = (
event.current_real - 
latest_time_).toSec();
 
   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);
 
   70     ROS_DEBUG_STREAM(
"G: (" << g_x << 
", " << g_y << 
", " << g_yaw << 
") detected");
 
   72     bool need_publish = 
false;
 
   96     dyn_srv_ = boost::make_shared<dyn::Server<Config> >(
pnh_);
 
  109 int main(
int argc, 
char** argv) {
 
  110   ros::init(argc, argv, 
"cmd_vel_smoother");
 
  
void dynConfigCallback(Config &cfg, uint32_t level)
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
boost::shared_ptr< dyn::Server< Config > > dyn_srv_
int main(int argc, char **argv)
#define ROS_DEBUG_STREAM(args)
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
void velCallback(const geometry_msgs::Twist::ConstPtr &msg)
void timerCallback(const ros::TimerEvent &event)
ros::Duration timerDuration()
void setPeriod(const Duration &period, bool reset=true)
geometry_msgs::Twist::ConstPtr latest_vel_
geometry_msgs::Twist::Ptr pub_vel_
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())
#define ROS_INFO_STREAM(args)
int interpolate_max_frame_
cmd_vel_smoother::CmdVelSmootherConfig Config
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
cmd_vel_smoother
Author(s): Yuki Furuta 
autogenerated on Mon Dec 9 2024 04:10:39