diff --git a/scout_base/src/scout_messenger.cpp b/scout_base/src/scout_messenger.cpp index 02870b0..3297bc4 100644 --- a/scout_base/src/scout_messenger.cpp +++ b/scout_base/src/scout_messenger.cpp @@ -13,6 +13,8 @@ #include "scout_msgs/ScoutStatus.h" +#include + namespace westonrobot { ScoutROSMessenger::ScoutROSMessenger(ros::NodeHandle *nh) : scout_(nullptr), nh_(nh) @@ -131,6 +133,7 @@ void ScoutROSMessenger::PublishStateToROS() current_time_ = ros::Time::now(); double dt = (current_time_ - last_time_).toSec(); + static bool init_run = true; if (init_run) { @@ -171,6 +174,9 @@ void ScoutROSMessenger::PublishStateToROS() // publish odometry and tf PublishOdometryToROS(state.linear_velocity, state.angular_velocity, dt); + // ROS_DEBUG("dt is %lg",dt); + std::cout<<"dt is"<