trajectory_execution_manager.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, 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 <moveit_msgs/RobotTrajectory.h>
43 #include <sensor_msgs/JointState.h>
44 #include <std_msgs/String.h>
45 #include <ros/ros.h>
47 #include <boost/thread.hpp>
49 
50 #include <memory>
51 
53 {
54 MOVEIT_CLASS_FORWARD(TrajectoryExecutionManager); // Defines TrajectoryExecutionManagerPtr, ConstPtr, WeakPtr... etc
55 
56 // Two modes:
57 // Managed controllers
58 // Unmanaged controllers: given the trajectory,
60 {
61 public:
62  static const std::string EXECUTION_EVENT_TOPIC;
63 
66  typedef boost::function<void(const moveit_controller_manager::ExecutionStatus&)> ExecutionCompleteCallback;
67 
70  using PathSegmentCompleteCallback = boost::function<void(std::size_t)>;
71 
73  struct TrajectoryExecutionContext
74  {
76  std::vector<std::string> controllers_;
77 
78  // The trajectory to execute, split in different parts (by joints), each set of joints corresponding to one
79  // controller
80  std::vector<moveit_msgs::RobotTrajectory> trajectory_parts_;
81  };
82 
84  TrajectoryExecutionManager(const moveit::core::RobotModelConstPtr& robot_model,
85  const planning_scene_monitor::CurrentStateMonitorPtr& csm);
86 
88  TrajectoryExecutionManager(const moveit::core::RobotModelConstPtr& robot_model,
89  const planning_scene_monitor::CurrentStateMonitorPtr& csm, bool manage_controllers);
90 
93 
95  bool isManagingControllers() const;
96 
98  const moveit_controller_manager::MoveItControllerManagerPtr& getControllerManager() const;
99 
101  void processEvent(const std::string& event);
102 
107  bool ensureActiveControllersForGroup(const std::string& group);
108 
113  bool ensureActiveControllersForJoints(const std::vector<std::string>& joints);
114 
118  bool ensureActiveController(const std::string& controller);
119 
123  bool ensureActiveControllers(const std::vector<std::string>& controllers);
124 
126  bool isControllerActive(const std::string& controller);
127 
129  bool areControllersActive(const std::vector<std::string>& controllers);
130 
133  bool push(const moveit_msgs::RobotTrajectory& trajectory, const std::string& controller = "");
134 
137  bool push(const trajectory_msgs::JointTrajectory& trajectory, const std::string& controller = "");
138 
144  bool push(const trajectory_msgs::JointTrajectory& trajectory, const std::vector<std::string>& controllers);
145 
151  bool push(const moveit_msgs::RobotTrajectory& trajectory, const std::vector<std::string>& controllers);
152 
154  const std::vector<TrajectoryExecutionContext*>& getTrajectories() const;
155 
157  void execute(const ExecutionCompleteCallback& callback = ExecutionCompleteCallback(), bool auto_clear = true);
158 
161  void execute(const ExecutionCompleteCallback& callback, const PathSegmentCompleteCallback& part_callback,
162  bool auto_clear = true);
163 
167 
171 
178  std::pair<int, int> getCurrentExpectedTrajectoryIndex() const;
179 
182 
184  void stopExecution(bool auto_clear = true);
185 
187  void clear();
188 
191  void enableExecutionDurationMonitoring(bool flag);
192 
195  void setAllowedExecutionDurationScaling(double scaling);
196 
199  void setAllowedGoalDurationMargin(double margin);
200 
203  void setExecutionVelocityScaling(double scaling);
204 
206  void setAllowedStartTolerance(double tolerance);
207 
209  void setWaitForTrajectoryCompletion(bool flag);
210 
211 private:
212  struct ControllerInformation
213  {
214  std::string name_;
215  std::set<std::string> joints_;
216  std::set<std::string> overlapping_controllers_;
219 
220  bool operator<(ControllerInformation& other) const
221  {
222  if (joints_.size() != other.joints_.size())
223  return joints_.size() < other.joints_.size();
224  return name_ < other.name_;
225  }
226  };
227 
228  void initialize();
229 
231 
233  bool validate(const TrajectoryExecutionContext& context) const;
234  bool configure(TrajectoryExecutionContext& context, const moveit_msgs::RobotTrajectory& trajectory,
235  const std::vector<std::string>& controllers);
236 
237  void updateControllersState(const ros::Duration& age);
238  void updateControllerState(const std::string& controller, const ros::Duration& age);
239  void updateControllerState(ControllerInformation& ci, const ros::Duration& age);
240 
241  bool distributeTrajectory(const moveit_msgs::RobotTrajectory& trajectory, const std::vector<std::string>& controllers,
242  std::vector<moveit_msgs::RobotTrajectory>& parts);
243 
244  bool findControllers(const std::set<std::string>& actuated_joints, std::size_t controller_count,
245  const std::vector<std::string>& available_controllers,
246  std::vector<std::string>& selected_controllers);
247  bool checkControllerCombination(std::vector<std::string>& controllers, const std::set<std::string>& actuated_joints);
248  void generateControllerCombination(std::size_t start_index, std::size_t controller_count,
249  const std::vector<std::string>& available_controllers,
250  std::vector<std::string>& selected_controllers,
251  std::vector<std::vector<std::string> >& selected_options,
252  const std::set<std::string>& actuated_joints);
253  bool selectControllers(const std::set<std::string>& actuated_joints,
254  const std::vector<std::string>& available_controllers,
255  std::vector<std::string>& selected_controllers);
256 
257  void executeThread(const ExecutionCompleteCallback& callback, const PathSegmentCompleteCallback& part_callback,
258  bool auto_clear);
259  bool executePart(std::size_t part_index);
260  bool waitForRobotToStop(const TrajectoryExecutionContext& context, double wait_time = 1.0);
261 
262  void stopExecutionInternal();
263 
264  void receiveEvent(const std_msgs::StringConstPtr& event);
265 
266  void loadControllerParams();
267 
268  double getJointAllowedStartTolerance(std::string const& jointName) const;
270 
271  moveit::core::RobotModelConstPtr robot_model_;
272  planning_scene_monitor::CurrentStateMonitorPtr csm_;
276 
277  std::map<std::string, ControllerInformation> known_controllers_;
278  bool manage_controllers_;
279 
280  // thread used to execute trajectories using the execute() command
281  std::unique_ptr<boost::thread> execution_thread_;
282 
283  boost::mutex execution_state_mutex_;
284  boost::mutex execution_thread_mutex_;
285 
286  // this condition is used to notify the completion of execution for given trajectories
287  boost::condition_variable execution_complete_condition_;
288 
290  std::vector<moveit_controller_manager::MoveItControllerHandlePtr> active_handles_;
291  int current_context_;
292  std::vector<ros::Time> time_index_; // used to find current expected trajectory location
293  mutable boost::mutex time_index_mutex_;
294  bool execution_complete_;
295 
296  std::vector<TrajectoryExecutionContext*> trajectories_;
297 
298  std::unique_ptr<pluginlib::ClassLoader<moveit_controller_manager::MoveItControllerManager> > controller_manager_loader_;
299  moveit_controller_manager::MoveItControllerManagerPtr controller_manager_;
300 
301  bool verbose_;
302 
305 
307  // 'global' values
310  // controller-specific values
311  // override the 'global' values
312  std::map<std::string, double> controller_allowed_execution_duration_scaling_;
313  std::map<std::string, double> controller_allowed_goal_duration_margin_;
314 
315  double allowed_start_tolerance_; // joint tolerance for validate(): radians for revolute joints
316  // tolerance per joint, overrides global allowed_start_tolerance_.
317  std::map<std::string, double> joints_allowed_start_tolerance_;
320 };
321 } // namespace trajectory_execution_manager
trajectory_execution_manager::TrajectoryExecutionManager::time_index_
std::vector< ros::Time > time_index_
Definition: trajectory_execution_manager.h:324
robot_model.h
trajectory_execution_manager::TrajectoryExecutionManager::validate
bool validate(const TrajectoryExecutionContext &context) const
Validate first point of trajectory matches current robot state.
Definition: trajectory_execution_manager.cpp:721
trajectory_execution_manager::TrajectoryExecutionManager::verbose_
bool verbose_
Definition: trajectory_execution_manager.h:333
trajectory_execution_manager::TrajectoryExecutionManager::ExecutionCompleteCallback
boost::function< void(const moveit_controller_manager::ExecutionStatus &)> ExecutionCompleteCallback
Definition: trajectory_execution_manager.h:98
trajectory_execution_manager::TrajectoryExecutionManager::execution_velocity_scaling_
double execution_velocity_scaling_
Definition: trajectory_execution_manager.h:350
trajectory_execution_manager::TrajectoryExecutionManager::execution_complete_condition_
boost::condition_variable execution_complete_condition_
Definition: trajectory_execution_manager.h:319
trajectory_execution_manager::TrajectoryExecutionManager
Definition: trajectory_execution_manager.h:91
trajectory_execution_manager::TrajectoryExecutionManager::executeAndWait
moveit_controller_manager::ExecutionStatus executeAndWait(bool auto_clear=true)
Definition: trajectory_execution_manager.cpp:932
trajectory_execution_manager::TrajectoryExecutionManager::controller_manager_loader_
std::unique_ptr< pluginlib::ClassLoader< moveit_controller_manager::MoveItControllerManager > > controller_manager_loader_
Definition: trajectory_execution_manager.h:330
trajectory_execution_manager::TrajectoryExecutionManager::stopExecution
void stopExecution(bool auto_clear=true)
Stop whatever executions are active, if any.
Definition: trajectory_execution_manager.cpp:952
trajectory_execution_manager::TrajectoryExecutionManager::setWaitForTrajectoryCompletion
void setWaitForTrajectoryCompletion(bool flag)
Enable or disable waiting for trajectory completion.
Definition: trajectory_execution_manager.cpp:213
ros.h
trajectory_execution_manager::TrajectoryExecutionManager::manage_controllers_
bool manage_controllers_
Definition: trajectory_execution_manager.h:310
trajectory_execution_manager::TrajectoryExecutionManager::ensureActiveController
bool ensureActiveController(const std::string &controller)
Make sure a particular controller is active.
Definition: trajectory_execution_manager.cpp:1442
trajectory_execution_manager::TrajectoryExecutionManager::selectControllers
bool selectControllers(const std::set< std::string > &actuated_joints, const std::vector< std::string > &available_controllers, std::vector< std::string > &selected_controllers)
Definition: trajectory_execution_manager.cpp:559
trajectory_execution_manager::TrajectoryExecutionManager::execution_complete_
bool execution_complete_
Definition: trajectory_execution_manager.h:326
trajectory_execution_manager::TrajectoryExecutionManager::setExecutionVelocityScaling
void setExecutionVelocityScaling(double scaling)
Definition: trajectory_execution_manager.cpp:203
trajectory_execution_manager::TrajectoryExecutionManager::csm_
planning_scene_monitor::CurrentStateMonitorPtr csm_
Definition: trajectory_execution_manager.h:304
trajectory_execution_manager::TrajectoryExecutionManager::node_handle_
ros::NodeHandle node_handle_
Definition: trajectory_execution_manager.h:305
trajectory_execution_manager::TrajectoryExecutionManager::ensureActiveControllersForJoints
bool ensureActiveControllersForJoints(const std::vector< std::string > &joints)
Make sure the active controllers are such that trajectories that actuate joints in the specified set ...
Definition: trajectory_execution_manager.cpp:1417
current_state_monitor.h
trajectory_execution_manager::TrajectoryExecutionManager::current_context_
int current_context_
Definition: trajectory_execution_manager.h:323
trajectory_execution_manager::TrajectoryExecutionManager::getLastExecutionStatus
moveit_controller_manager::ExecutionStatus getLastExecutionStatus() const
Return the controller status for the last attempted execution.
Definition: trajectory_execution_manager.cpp:1403
trajectory_execution_manager::TrajectoryExecutionManager::isControllerActive
bool isControllerActive(const std::string &controller)
Check if a controller is active.
Definition: trajectory_execution_manager.cpp:542
trajectory_execution_manager::TrajectoryExecutionManager::last_execution_status_
moveit_controller_manager::ExecutionStatus last_execution_status_
Definition: trajectory_execution_manager.h:321
trajectory_execution_manager::TrajectoryExecutionManager::initialize
void initialize()
Definition: trajectory_execution_manager.cpp:109
trajectory_execution_manager::TrajectoryExecutionManager::ensureActiveControllers
bool ensureActiveControllers(const std::vector< std::string > &controllers)
Make sure a particular set of controllers are active.
Definition: trajectory_execution_manager.cpp:1447
trajectory_execution_manager::TrajectoryExecutionManager::checkControllerCombination
bool checkControllerCombination(std::vector< std::string > &controllers, const std::set< std::string > &actuated_joints)
Definition: trajectory_execution_manager.cpp:367
trajectory_execution_manager::TrajectoryExecutionManager::setAllowedExecutionDurationScaling
void setAllowedExecutionDurationScaling(double scaling)
Definition: trajectory_execution_manager.cpp:193
trajectory_execution_manager::TrajectoryExecutionManager::controller_allowed_goal_duration_margin_
std::map< std::string, double > controller_allowed_goal_duration_margin_
Definition: trajectory_execution_manager.h:345
controller_manager.h
trajectory_execution_manager::TrajectoryExecutionManager::receiveEvent
void receiveEvent(const std_msgs::StringConstPtr &event)
Definition: trajectory_execution_manager.cpp:236
trajectory_execution_manager::TrajectoryExecutionManager::getTrajectories
const std::vector< TrajectoryExecutionContext * > & getTrajectories() const
Get the trajectories to be executed.
Definition: trajectory_execution_manager.cpp:1398
trajectory_execution_manager::TrajectoryExecutionManager::controller_manager_
moveit_controller_manager::MoveItControllerManagerPtr controller_manager_
Definition: trajectory_execution_manager.h:331
trajectory_execution_manager::TrajectoryExecutionManager::execution_duration_monitoring_
bool execution_duration_monitoring_
Definition: trajectory_execution_manager.h:338
trajectory_execution_manager::TrajectoryExecutionManager::stopExecutionInternal
void stopExecutionInternal()
Definition: trajectory_execution_manager.cpp:938
trajectory_execution_manager::TrajectoryExecutionManager::TrajectoryExecutionContext::trajectory_parts_
std::vector< moveit_msgs::RobotTrajectory > trajectory_parts_
Definition: trajectory_execution_manager.h:112
trajectory_execution_manager::MOVEIT_CLASS_FORWARD
MOVEIT_CLASS_FORWARD(TrajectoryExecutionManager)
trajectory_execution_manager::TrajectoryExecutionManager::ControllerInformation::name_
std::string name_
Definition: trajectory_execution_manager.h:246
trajectory_execution_manager::TrajectoryExecutionManager::reconfigure_impl_
DynamicReconfigureImpl * reconfigure_impl_
Definition: trajectory_execution_manager.h:335
trajectory_execution_manager::TrajectoryExecutionManager::root_node_handle_
ros::NodeHandle root_node_handle_
Definition: trajectory_execution_manager.h:306
trajectory_execution_manager::TrajectoryExecutionManager::executePart
bool executePart(std::size_t part_index)
Definition: trajectory_execution_manager.cpp:1110
trajectory_execution_manager::TrajectoryExecutionManager::allowed_start_tolerance_
double allowed_start_tolerance_
Definition: trajectory_execution_manager.h:347
trajectory_execution_manager::TrajectoryExecutionManager::generateControllerCombination
void generateControllerCombination(std::size_t start_index, std::size_t controller_count, const std::vector< std::string > &available_controllers, std::vector< std::string > &selected_controllers, std::vector< std::vector< std::string > > &selected_options, const std::set< std::string > &actuated_joints)
Definition: trajectory_execution_manager.cpp:393
trajectory_execution_manager::TrajectoryExecutionManager::ControllerInformation
Definition: trajectory_execution_manager.h:244
trajectory_execution_manager::TrajectoryExecutionManager::DynamicReconfigureImpl
Definition: trajectory_execution_manager.cpp:60
trajectory_execution_manager::TrajectoryExecutionManager::ControllerInformation::operator<
bool operator<(ControllerInformation &other) const
Definition: trajectory_execution_manager.h:252
trajectory_execution_manager::TrajectoryExecutionManager::execute
void execute(const ExecutionCompleteCallback &callback=ExecutionCompleteCallback(), bool auto_clear=true)
Start the execution of pushed trajectories; this does not wait for completion, but calls a callback w...
Definition: trajectory_execution_manager.cpp:997
trajectory_execution_manager::TrajectoryExecutionManager::trajectories_
std::vector< TrajectoryExecutionContext * > trajectories_
Definition: trajectory_execution_manager.h:328
trajectory_execution_manager
Definition: trajectory_execution_manager.h:52
trajectory_execution_manager::TrajectoryExecutionManager::areControllersActive
bool areControllersActive(const std::vector< std::string > &controllers)
Check if a set of controllers are active.
Definition: trajectory_execution_manager.cpp:547
trajectory_execution_manager::TrajectoryExecutionManager::active_handles_
std::vector< moveit_controller_manager::MoveItControllerHandlePtr > active_handles_
Definition: trajectory_execution_manager.h:322
trajectory_execution_manager::TrajectoryExecutionManager::TrajectoryExecutionContext::controllers_
std::vector< std::string > controllers_
The controllers to use for executing the different trajectory parts;.
Definition: trajectory_execution_manager.h:108
moveit_controller_manager::MoveItControllerManager::ControllerState
trajectory_execution_manager::TrajectoryExecutionManager::EXECUTION_EVENT_TOPIC
static const std::string EXECUTION_EVENT_TOPIC
Definition: trajectory_execution_manager.h:94
class_loader.hpp
trajectory_execution_manager::TrajectoryExecutionManager::ControllerInformation::overlapping_controllers_
std::set< std::string > overlapping_controllers_
Definition: trajectory_execution_manager.h:248
trajectory_execution_manager::TrajectoryExecutionManager::getControllerManager
const moveit_controller_manager::MoveItControllerManagerPtr & getControllerManager() const
Get the instance of the controller manager used (this is the plugin instance loaded)
Definition: trajectory_execution_manager.cpp:223
trajectory_execution_manager::TrajectoryExecutionManager::processEvent
void processEvent(const std::string &event)
Execute a named event (e.g., 'stop')
Definition: trajectory_execution_manager.cpp:228
trajectory_execution_manager::TrajectoryExecutionManager::setAllowedGoalDurationMargin
void setAllowedGoalDurationMargin(double margin)
Definition: trajectory_execution_manager.cpp:198
trajectory_execution_manager::TrajectoryExecutionManager::updateJointsAllowedStartTolerance
void updateJointsAllowedStartTolerance()
Definition: trajectory_execution_manager.cpp:1574
trajectory_execution_manager::TrajectoryExecutionManager::findControllers
bool findControllers(const std::set< std::string > &actuated_joints, std::size_t controller_count, const std::vector< std::string > &available_controllers, std::vector< std::string > &selected_controllers)
Definition: trajectory_execution_manager.cpp:458
trajectory_execution_manager::TrajectoryExecutionManager::ControllerInformation::state_
moveit_controller_manager::MoveItControllerManager::ControllerState state_
Definition: trajectory_execution_manager.h:249
trajectory_execution_manager::TrajectoryExecutionManager::execution_thread_mutex_
boost::mutex execution_thread_mutex_
Definition: trajectory_execution_manager.h:316
trajectory_execution_manager::TrajectoryExecutionManager::updateControllerState
void updateControllerState(const std::string &controller, const ros::Duration &age)
Definition: trajectory_execution_manager.cpp:336
trajectory_execution_manager::TrajectoryExecutionManager::reloadControllerInformation
void reloadControllerInformation()
Definition: trajectory_execution_manager.cpp:301
trajectory_execution_manager::TrajectoryExecutionManager::updateControllersState
void updateControllersState(const ros::Duration &age)
Definition: trajectory_execution_manager.cpp:361
trajectory_execution_manager::TrajectoryExecutionManager::getCurrentExpectedTrajectoryIndex
std::pair< int, int > getCurrentExpectedTrajectoryIndex() const
Definition: trajectory_execution_manager.cpp:1384
ros::Time
selected_options
std::vector< std::vector< std::string > > selected_options
Definition: trajectory_execution_manager.cpp:451
class_forward.h
trajectory_execution_manager::TrajectoryExecutionManager::ControllerInformation::joints_
std::set< std::string > joints_
Definition: trajectory_execution_manager.h:247
trajectory_execution_manager::TrajectoryExecutionManager::robot_model_
moveit::core::RobotModelConstPtr robot_model_
Definition: trajectory_execution_manager.h:303
trajectory_execution_manager::TrajectoryExecutionManager::executeThread
void executeThread(const ExecutionCompleteCallback &callback, const PathSegmentCompleteCallback &part_callback, bool auto_clear)
Definition: trajectory_execution_manager.cpp:1057
trajectory_execution_manager::TrajectoryExecutionManager::waitForExecution
moveit_controller_manager::ExecutionStatus waitForExecution()
Definition: trajectory_execution_manager.cpp:1031
trajectory_execution_manager::TrajectoryExecutionManager::~TrajectoryExecutionManager
~TrajectoryExecutionManager()
Destructor. Cancels all running trajectories (if any)
Definition: trajectory_execution_manager.cpp:103
trajectory_execution_manager::TrajectoryExecutionManager::TrajectoryExecutionManager
TrajectoryExecutionManager(const moveit::core::RobotModelConstPtr &robot_model, const planning_scene_monitor::CurrentStateMonitorPtr &csm)
Load the controller manager plugin, start listening for events on a topic.
Definition: trajectory_execution_manager.cpp:85
trajectory_execution_manager::TrajectoryExecutionManager::configure
bool configure(TrajectoryExecutionContext &context, const moveit_msgs::RobotTrajectory &trajectory, const std::vector< std::string > &controllers)
Definition: trajectory_execution_manager.cpp:822
trajectory_execution_manager::TrajectoryExecutionManager::ensureActiveControllersForGroup
bool ensureActiveControllersForGroup(const std::string &group)
Make sure the active controllers are such that trajectories that actuate joints in the specified grou...
Definition: trajectory_execution_manager.cpp:1408
trajectory_execution_manager::TrajectoryExecutionManager::joints_allowed_start_tolerance_
std::map< std::string, double > joints_allowed_start_tolerance_
Definition: trajectory_execution_manager.h:349
trajectory_execution_manager::TrajectoryExecutionManager::wait_for_trajectory_completion_
bool wait_for_trajectory_completion_
Definition: trajectory_execution_manager.h:351
trajectory_execution_manager::TrajectoryExecutionManager::ControllerInformation::last_update_
ros::Time last_update_
Definition: trajectory_execution_manager.h:250
trajectory_execution_manager::TrajectoryExecutionManager::allowed_goal_duration_margin_
double allowed_goal_duration_margin_
Definition: trajectory_execution_manager.h:341
trajectory_execution_manager::TrajectoryExecutionManager::distributeTrajectory
bool distributeTrajectory(const moveit_msgs::RobotTrajectory &trajectory, const std::vector< std::string > &controllers, std::vector< moveit_msgs::RobotTrajectory > &parts)
Definition: trajectory_execution_manager.cpp:585
trajectory_execution_manager::TrajectoryExecutionManager::clear
void clear()
Clear the trajectories to execute.
Definition: trajectory_execution_manager.cpp:1045
trajectory_execution_manager::TrajectoryExecutionManager::execution_state_mutex_
boost::mutex execution_state_mutex_
Definition: trajectory_execution_manager.h:315
trajectory_execution_manager::TrajectoryExecutionManager::push
bool push(const moveit_msgs::RobotTrajectory &trajectory, const std::string &controller="")
Definition: trajectory_execution_manager.cpp:242
trajectory_execution_manager::TrajectoryExecutionManager::execution_thread_
std::unique_ptr< boost::thread > execution_thread_
Definition: trajectory_execution_manager.h:313
trajectory_execution_manager::TrajectoryExecutionManager::time_index_mutex_
boost::mutex time_index_mutex_
Definition: trajectory_execution_manager.h:325
trajectory_execution_manager::TrajectoryExecutionManager::getJointAllowedStartTolerance
double getJointAllowedStartTolerance(std::string const &jointName) const
Definition: trajectory_execution_manager.cpp:1567
trajectory_execution_manager::TrajectoryExecutionManager::controller_allowed_execution_duration_scaling_
std::map< std::string, double > controller_allowed_execution_duration_scaling_
Definition: trajectory_execution_manager.h:344
trajectory_execution_manager::TrajectoryExecutionManager::isManagingControllers
bool isManagingControllers() const
If this function returns true, then this instance of the manager is allowed to load/unload/switch con...
Definition: trajectory_execution_manager.cpp:218
trajectory_execution_manager::TrajectoryExecutionManager::event_topic_subscriber_
ros::Subscriber event_topic_subscriber_
Definition: trajectory_execution_manager.h:307
trajectory_execution_manager::TrajectoryExecutionManager::allowed_execution_duration_scaling_
double allowed_execution_duration_scaling_
Definition: trajectory_execution_manager.h:340
trajectory_execution_manager::TrajectoryExecutionManager::enableExecutionDurationMonitoring
void enableExecutionDurationMonitoring(bool flag)
Definition: trajectory_execution_manager.cpp:188
ros::Duration
trajectory_execution_manager::TrajectoryExecutionManager::waitForRobotToStop
bool waitForRobotToStop(const TrajectoryExecutionContext &context, double wait_time=1.0)
Definition: trajectory_execution_manager.cpp:1324
trajectory_execution_manager::TrajectoryExecutionManager::TrajectoryExecutionContext
Data structure that represents information necessary to execute a trajectory.
Definition: trajectory_execution_manager.h:105
moveit_controller_manager::ExecutionStatus
trajectory_execution_manager::TrajectoryExecutionManager::PathSegmentCompleteCallback
boost::function< void(std::size_t)> PathSegmentCompleteCallback
Definition: trajectory_execution_manager.h:102
ros::NodeHandle
ros::Subscriber
trajectory_execution_manager::TrajectoryExecutionManager::known_controllers_
std::map< std::string, ControllerInformation > known_controllers_
Definition: trajectory_execution_manager.h:309
trajectory_execution_manager::TrajectoryExecutionManager::setAllowedStartTolerance
void setAllowedStartTolerance(double tolerance)
Set joint-value tolerance for validating trajectory's start point against current robot state.
Definition: trajectory_execution_manager.cpp:208
trajectory_execution_manager::TrajectoryExecutionManager::loadControllerParams
void loadControllerParams()
Definition: trajectory_execution_manager.cpp:1545


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Thu Apr 18 2024 02:24:19