43 static const std::string 
LOGNAME = 
"TrajectoryMonitor";
 
   46                                                              double sampling_frequency)
 
   47   : current_state_monitor_(state_monitor)
 
   48   , sampling_frequency_(sampling_frequency)
 
   49   , trajectory_(current_state_monitor_->getRobotModel(), 
"")
 
   56   stopTrajectoryMonitor();
 
   61   if (sampling_frequency == sampling_frequency_)
 
   64   if (sampling_frequency <= std::numeric_limits<double>::epsilon())
 
   68   sampling_frequency_ = sampling_frequency;
 
   73   return static_cast<bool>(record_states_thread_);
 
   78   if (sampling_frequency_ > std::numeric_limits<double>::epsilon() && !record_states_thread_)
 
   80     record_states_thread_ = std::make_unique<boost::thread>([
this] { recordStates(); });
 
   87   if (record_states_thread_)
 
   89     std::unique_ptr<boost::thread> copy;
 
   90     copy.swap(record_states_thread_);
 
   98   bool restart = isActive();
 
  100     stopTrajectoryMonitor();
 
  103     startTrajectoryMonitor();
 
  108   if (!current_state_monitor_)
 
  113   while (record_states_thread_)
 
  116     std::pair<moveit::core::RobotStatePtr, ros::Time> state = current_state_monitor_->getCurrentStateAndTime();
 
  117     if (trajectory_.empty())
 
  119       trajectory_.addSuffixWayPoint(state.first, 0.0);
 
  120       trajectory_start_time_ = state.second;
 
  121       last_recorded_state_time_ = state.second;
 
  125       trajectory_.addSuffixWayPoint(state.first, (state.second - last_recorded_state_time_).toSec());
 
  126       last_recorded_state_time_ = state.second;
 
  128     if (state_add_callback_)
 
  129       state_add_callback_(state.first, state.second);