43 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit_ros.planning_scene_monitor.trajectory_monitor");
46 double sampling_frequency)
53 const CurrentStateMonitorConstPtr& state_monitor,
54 std::unique_ptr<TrajectoryMonitor::MiddlewareHandle> middleware_handle,
double sampling_frequency)
55 : current_state_monitor_(state_monitor)
56 , middleware_handle_(std::move(middleware_handle))
57 , sampling_frequency_(sampling_frequency)
58 , trajectory_(current_state_monitor_->getRobotModel(),
"")
65 stopTrajectoryMonitor();
70 if (sampling_frequency == sampling_frequency_)
73 if (sampling_frequency <= std::numeric_limits<double>::epsilon())
74 RCLCPP_ERROR(LOGGER,
"The sampling frequency for trajectory states should be positive");
76 RCLCPP_DEBUG(LOGGER,
"Setting trajectory sampling frequency to %.1f", sampling_frequency);
77 sampling_frequency_ = sampling_frequency;
82 return static_cast<bool>(record_states_thread_);
87 if (sampling_frequency_ > std::numeric_limits<double>::epsilon() && !record_states_thread_)
89 record_states_thread_ = std::make_unique<std::thread>([
this] { recordStates(); });
90 RCLCPP_DEBUG(LOGGER,
"Started trajectory monitor");
96 if (record_states_thread_)
98 std::unique_ptr<std::thread> copy;
99 copy.swap(record_states_thread_);
101 RCLCPP_DEBUG(LOGGER,
"Stopped trajectory monitor");
107 bool restart = isActive();
109 stopTrajectoryMonitor();
112 startTrajectoryMonitor();
115 void planning_scene_monitor::TrajectoryMonitor::recordStates()
117 if (!current_state_monitor_)
120 middleware_handle_->setRate(sampling_frequency_);
122 while (record_states_thread_)
124 middleware_handle_->sleep();
125 std::pair<moveit::core::RobotStatePtr, rclcpp::Time> state = current_state_monitor_->getCurrentStateAndTime();
126 if (trajectory_.empty())
128 trajectory_.addSuffixWayPoint(state.first, 0.0);
129 trajectory_start_time_ = state.second;
130 last_recorded_state_time_ = state.second;
134 trajectory_.addSuffixWayPoint(state.first, (state.second - last_recorded_state_time_).seconds());
135 last_recorded_state_time_ = state.second;
137 if (state_add_callback_)
138 state_add_callback_(state.first, state.second);
This class contains the ROS2 interfaces for TrajectoryMonitor. This class is useful for testing by mo...
Monitors the joint_states topic and tf to record the trajectory of the robot.
void stopTrajectoryMonitor()
TrajectoryMonitor(const CurrentStateMonitorConstPtr &state_monitor, double sampling_frequency=0.0)
Constructor.
void startTrajectoryMonitor()
void setSamplingFrequency(double sampling_frequency)
const rclcpp::Logger LOGGER