trajectory_monitor.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
37 #pragma once
38 
42 #include <boost/thread.hpp>
43 #include <memory>
44 
45 namespace planning_scene_monitor
46 {
47 using TrajectoryStateAddedCallback = boost::function<void(const moveit::core::RobotStateConstPtr&, const ros::Time&)>;
48 
49 MOVEIT_CLASS_FORWARD(TrajectoryMonitor); // Defines TrajectoryMonitorPtr, ConstPtr, WeakPtr... etc
50 
52 class TrajectoryMonitor
53 {
54 public:
57  TrajectoryMonitor(const CurrentStateMonitorConstPtr& state_monitor, double sampling_frequency = 0.0);
58 
60 
62 
63  void stopTrajectoryMonitor();
64 
65  void clearTrajectory();
66 
67  bool isActive() const;
68 
69  double getSamplingFrequency() const
70  {
71  return sampling_frequency_;
72  }
73 
74  void setSamplingFrequency(double sampling_frequency);
75 
79  {
80  return trajectory_;
81  }
82 
84  {
85  trajectory_.swap(other);
86  }
87 
89  {
90  state_add_callback_ = callback;
91  }
92 
93 private:
94  void recordStates();
95 
96  CurrentStateMonitorConstPtr current_state_monitor_;
97  double sampling_frequency_;
98 
102 
103  std::unique_ptr<boost::thread> record_states_thread_;
105 };
106 } // namespace planning_scene_monitor
planning_scene_monitor
Definition: current_state_monitor.h:47
planning_scene_monitor::TrajectoryMonitor::record_states_thread_
std::unique_ptr< boost::thread > record_states_thread_
Definition: trajectory_monitor.h:135
planning_scene_monitor::TrajectoryMonitor::last_recorded_state_time_
ros::Time last_recorded_state_time_
Definition: trajectory_monitor.h:133
planning_scene_monitor::TrajectoryMonitor::recordStates
void recordStates()
Definition: trajectory_monitor.cpp:106
planning_scene_monitor::TrajectoryMonitor::trajectory_start_time_
ros::Time trajectory_start_time_
Definition: trajectory_monitor.h:132
planning_scene_monitor::TrajectoryMonitor::getTrajectory
const robot_trajectory::RobotTrajectory & getTrajectory()
Definition: trajectory_monitor.h:110
planning_scene_monitor::TrajectoryMonitor::current_state_monitor_
CurrentStateMonitorConstPtr current_state_monitor_
Definition: trajectory_monitor.h:128
current_state_monitor.h
planning_scene_monitor::TrajectoryMonitor::clearTrajectory
void clearTrajectory()
Definition: trajectory_monitor.cpp:96
robot_trajectory::RobotTrajectory
planning_scene_monitor::TrajectoryMonitor::sampling_frequency_
double sampling_frequency_
Definition: trajectory_monitor.h:129
planning_scene_monitor::TrajectoryMonitor::stopTrajectoryMonitor
void stopTrajectoryMonitor()
Definition: trajectory_monitor.cpp:85
robot_trajectory.h
planning_scene_monitor::TrajectoryStateAddedCallback
boost::function< void(const moveit::core::RobotStateConstPtr &, const ros::Time &)> TrajectoryStateAddedCallback
Definition: trajectory_monitor.h:79
planning_scene_monitor::TrajectoryMonitor::swapTrajectory
void swapTrajectory(robot_trajectory::RobotTrajectory &other)
Definition: trajectory_monitor.h:115
planning_scene_monitor::TrajectoryMonitor::setOnStateAddCallback
void setOnStateAddCallback(const TrajectoryStateAddedCallback &callback)
Definition: trajectory_monitor.h:120
planning_scene_monitor::TrajectoryMonitor::isActive
bool isActive() const
Definition: trajectory_monitor.cpp:71
planning_scene_monitor::TrajectoryMonitor::TrajectoryMonitor
TrajectoryMonitor(const CurrentStateMonitorConstPtr &state_monitor, double sampling_frequency=0.0)
Constructor.
Definition: trajectory_monitor.cpp:45
planning_scene_monitor::TrajectoryMonitor::trajectory_
robot_trajectory::RobotTrajectory trajectory_
Definition: trajectory_monitor.h:131
planning_scene_monitor::TrajectoryMonitor::~TrajectoryMonitor
~TrajectoryMonitor()
Definition: trajectory_monitor.cpp:54
planning_scene_monitor::MOVEIT_CLASS_FORWARD
MOVEIT_CLASS_FORWARD(CurrentStateMonitor)
planning_scene_monitor::TrajectoryMonitor::state_add_callback_
TrajectoryStateAddedCallback state_add_callback_
Definition: trajectory_monitor.h:136
ros::Time
class_forward.h
planning_scene_monitor::TrajectoryMonitor::startTrajectoryMonitor
void startTrajectoryMonitor()
Definition: trajectory_monitor.cpp:76
planning_scene_monitor::TrajectoryMonitor::getSamplingFrequency
double getSamplingFrequency() const
Definition: trajectory_monitor.h:101
planning_scene_monitor::TrajectoryMonitor::setSamplingFrequency
void setSamplingFrequency(double sampling_frequency)
Definition: trajectory_monitor.cpp:59
robot_trajectory::RobotTrajectory::swap
void swap(robot_trajectory::RobotTrajectory &other)


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Thu Nov 21 2024 03:24:18