37 #ifndef MOVEIT_PLANNING_SCENE_MONITOR_TRAJECTORY_MONITOR_ 38 #define MOVEIT_PLANNING_SCENE_MONITOR_TRAJECTORY_MONITOR_ 43 #include <boost/thread.hpp> 48 typedef boost::function<void(const robot_state::RobotStateConstPtr& state, const ros::Time& stamp)>
60 TrajectoryMonitor(
const CurrentStateMonitorConstPtr& state_monitor,
double sampling_frequency = 5.0);
void swap(robot_trajectory::RobotTrajectory &other)
void setOnStateAddCallback(const TrajectoryStateAddedCallback &callback)
void stopTrajectoryMonitor()
void startTrajectoryMonitor()
std::unique_ptr< boost::thread > record_states_thread_
robot_trajectory::RobotTrajectory trajectory_
ros::Time trajectory_start_time_
TrajectoryStateAddedCallback state_add_callback_
double getSamplingFrequency() const
const robot_trajectory::RobotTrajectory & getTrajectory()
CurrentStateMonitorConstPtr current_state_monitor_
TrajectoryMonitor(const CurrentStateMonitorConstPtr &state_monitor, double sampling_frequency=5.0)
Constructor.
MOVEIT_CLASS_FORWARD(CurrentStateMonitor)
Monitors the joint_states topic and tf to record the trajectory of the robot.
double sampling_frequency_
void setSamplingFrequency(double sampling_frequency)
boost::function< void(const robot_state::RobotStateConstPtr &state, const ros::Time &stamp)> TrajectoryStateAddedCallback
void swapTrajectory(robot_trajectory::RobotTrajectory &other)
ros::Time last_recorded_state_time_