Monitors the joint_states topic and tf to record the trajectory of the robot. More...
#include <trajectory_monitor.h>
Public Member Functions | |
void | clearTrajectory () |
double | getSamplingFrequency () const |
const robot_trajectory::RobotTrajectory & | getTrajectory () |
bool | isActive () const |
void | setOnStateAddCallback (const TrajectoryStateAddedCallback &callback) |
void | setSamplingFrequency (double sampling_frequency) |
void | startTrajectoryMonitor () |
void | stopTrajectoryMonitor () |
void | swapTrajectory (robot_trajectory::RobotTrajectory &other) |
TrajectoryMonitor (const CurrentStateMonitorConstPtr &state_monitor, double sampling_frequency=5.0) | |
Constructor. | |
~TrajectoryMonitor () | |
Private Member Functions | |
void | recordStates () |
Private Attributes | |
CurrentStateMonitorConstPtr | current_state_monitor_ |
ros::Time | last_recorded_state_time_ |
boost::scoped_ptr< boost::thread > | record_states_thread_ |
double | sampling_frequency_ |
TrajectoryStateAddedCallback | state_add_callback_ |
robot_trajectory::RobotTrajectory | trajectory_ |
ros::Time | trajectory_start_time_ |
Monitors the joint_states topic and tf to record the trajectory of the robot.
Definition at line 54 of file trajectory_monitor.h.
planning_scene_monitor::TrajectoryMonitor::TrajectoryMonitor | ( | const CurrentStateMonitorConstPtr & | state_monitor, |
double | sampling_frequency = 5.0 |
||
) |
Constructor.
Definition at line 42 of file trajectory_monitor.cpp.
Definition at line 51 of file trajectory_monitor.cpp.
Definition at line 89 of file trajectory_monitor.cpp.
double planning_scene_monitor::TrajectoryMonitor::getSamplingFrequency | ( | ) | const [inline] |
Definition at line 71 of file trajectory_monitor.h.
const robot_trajectory::RobotTrajectory& planning_scene_monitor::TrajectoryMonitor::getTrajectory | ( | ) | [inline] |
Return the current maintained trajectory. This function is not thread safe (hence NOT const), because the trajectory could be modified.
Definition at line 80 of file trajectory_monitor.h.
bool planning_scene_monitor::TrajectoryMonitor::isActive | ( | ) | const |
Definition at line 64 of file trajectory_monitor.cpp.
void planning_scene_monitor::TrajectoryMonitor::recordStates | ( | ) | [private] |
Definition at line 99 of file trajectory_monitor.cpp.
void planning_scene_monitor::TrajectoryMonitor::setOnStateAddCallback | ( | const TrajectoryStateAddedCallback & | callback | ) | [inline] |
Definition at line 90 of file trajectory_monitor.h.
void planning_scene_monitor::TrajectoryMonitor::setSamplingFrequency | ( | double | sampling_frequency | ) |
Definition at line 56 of file trajectory_monitor.cpp.
Definition at line 69 of file trajectory_monitor.cpp.
Definition at line 78 of file trajectory_monitor.cpp.
void planning_scene_monitor::TrajectoryMonitor::swapTrajectory | ( | robot_trajectory::RobotTrajectory & | other | ) | [inline] |
Definition at line 85 of file trajectory_monitor.h.
CurrentStateMonitorConstPtr planning_scene_monitor::TrajectoryMonitor::current_state_monitor_ [private] |
Definition at line 98 of file trajectory_monitor.h.
Definition at line 103 of file trajectory_monitor.h.
boost::scoped_ptr<boost::thread> planning_scene_monitor::TrajectoryMonitor::record_states_thread_ [private] |
Definition at line 105 of file trajectory_monitor.h.
double planning_scene_monitor::TrajectoryMonitor::sampling_frequency_ [private] |
Definition at line 99 of file trajectory_monitor.h.
TrajectoryStateAddedCallback planning_scene_monitor::TrajectoryMonitor::state_add_callback_ [private] |
Definition at line 106 of file trajectory_monitor.h.
Definition at line 101 of file trajectory_monitor.h.
Definition at line 102 of file trajectory_monitor.h.