43#include <rclcpp/time.hpp>
73 virtual void setRate(
double sampling_frequency) = 0;
85 TrajectoryMonitor(
const CurrentStateMonitorConstPtr& state_monitor,
double sampling_frequency = 0.0);
92 std::unique_ptr<MiddlewareHandle> middleware_handle,
double sampling_frequency = 0.0);
106 return sampling_frequency_;
120 trajectory_.
swap(other);
125 state_add_callback_ = callback;
132 CurrentStateMonitorConstPtr current_state_monitor_;
134 std::unique_ptr<MiddlewareHandle> middleware_handle_;
135 double sampling_frequency_;
138 rclcpp::Time trajectory_start_time_;
139 rclcpp::Time last_recorded_state_time_;
141 std::unique_ptr<std::thread> record_states_thread_;
144 rclcpp::Logger logger_;
#define MOVEIT_CLASS_FORWARD(C)
This class contains the rcl interfaces for easier testing.
virtual void sleep()=0
Sleep the handle for some prescribed amount of time.
virtual void setRate(double sampling_frequency)=0
set Rate using sampling frequency
virtual ~MiddlewareHandle()=default
Destroys the object.
Monitors the joint_states topic and tf to record the trajectory of the robot.
void swapTrajectory(robot_trajectory::RobotTrajectory &other)
void stopTrajectoryMonitor()
const robot_trajectory::RobotTrajectory & getTrajectory()
double getSamplingFrequency() const
TrajectoryMonitor(const CurrentStateMonitorConstPtr &state_monitor, std::unique_ptr< MiddlewareHandle > middleware_handle, double sampling_frequency=0.0)
Constructor with middleware handle as input parameter.
void startTrajectoryMonitor()
void setSamplingFrequency(double sampling_frequency)
void setOnStateAddCallback(const TrajectoryStateAddedCallback &callback)
Maintain a sequence of waypoints and the time durations between these waypoints.
void swap(robot_trajectory::RobotTrajectory &other) noexcept
std::function< void(const moveit::core::RobotStateConstPtr &, const rclcpp::Time &)> TrajectoryStateAddedCallback