Classes | Public Types | Public Member Functions | Static Public Attributes | Private Member Functions | Private Attributes
trajectory_execution_manager::TrajectoryExecutionManager Class Reference

#include <trajectory_execution_manager.h>

List of all members.

Classes

struct  ControllerInformation
class  DynamicReconfigureImpl
struct  TrajectoryExecutionContext
 Data structure that represents information necessary to execute a trajectory. More...

Public Types

typedef boost::function< void(const
moveit_controller_manager::ExecutionStatus &)> 
ExecutionCompleteCallback
 Definition of the function signature that is called when the execution of all the pushed trajectories completes. The status of the overall execution is passed as argument.
typedef boost::function< void(std::size_t)> PathSegmentCompleteCallback
 Definition of the function signature that is called when the execution of a pushed trajectory completes successfully.

Public Member Functions

bool areControllersActive (const std::vector< std::string > &controllers)
 Check if a set of controllers are active.
void clear ()
 Clear the trajectories to execute.
void enableExecutionDurationMonitoring (bool flag)
bool ensureActiveController (const std::string &controller)
 Make sure a particular controller is active.
bool ensureActiveControllers (const std::vector< std::string > &controllers)
 Make sure a particular set of controllers are active.
bool ensureActiveControllersForGroup (const std::string &group)
 Make sure the active controllers are such that trajectories that actuate joints in the specified group can be executed.
bool ensureActiveControllersForJoints (const std::vector< std::string > &joints)
 Make sure the active controllers are such that trajectories that actuate joints in the specified set can be executed.
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 when done.
void execute (const ExecutionCompleteCallback &callback, const PathSegmentCompleteCallback &part_callback, bool auto_clear=true)
 Start the execution of pushed trajectories; this does not wait for completion, but calls a callback when done. A callback is also called for every trajectory part that completes successfully.
moveit_controller_manager::ExecutionStatus executeAndWait (bool auto_clear=true)
 This is a blocking call for the execution of the passed in trajectories. This just calls execute() and waitForExecution()
const
moveit_controller_manager::MoveItControllerManagerPtr
getControllerManager () const
 Get the instance of the controller manager used (this is the plugin instance loaded)
std::pair< int, int > getCurrentExpectedTrajectoryIndex () const
moveit_controller_manager::ExecutionStatus getLastExecutionStatus () const
 Return the controller status for the last attempted execution.
const std::vector
< TrajectoryExecutionContext * > & 
getTrajectories () const
 Get the trajectories to be executed.
bool isControllerActive (const std::string &controller)
 Check if a controller is active.
bool isManagingControllers () const
 If this function returns true, then this instance of the manager is allowed to load/unload/switch controllers.
void processEvent (const std::string &event)
 Execute a named event (e.g., 'stop')
bool push (const moveit_msgs::RobotTrajectory &trajectory, const std::string &controller="")
 Add a trajectory for future execution. Optionally specify a controller to use for the trajectory. If no controller is specified, a default is used.
bool push (const trajectory_msgs::JointTrajectory &trajectory, const std::string &controller="")
 Add a trajectory for future execution. Optionally specify a controller to use for the trajectory. If no controller is specified, a default is used.
bool push (const trajectory_msgs::JointTrajectory &trajectory, const std::vector< std::string > &controllers)
bool push (const moveit_msgs::RobotTrajectory &trajectory, const std::vector< std::string > &controllers)
bool pushAndExecute (const moveit_msgs::RobotTrajectory &trajectory, const std::string &controller="")
 Add a trajectory for immediate execution. Optionally specify a controller to use for the trajectory. If no controller is specified, a default is used. This call is non-blocking.
bool pushAndExecute (const trajectory_msgs::JointTrajectory &trajectory, const std::string &controller="")
 Add a trajectory for immediate execution. Optionally specify a controller to use for the trajectory. If no controller is specified, a default is used. This call is non-blocking.
bool pushAndExecute (const sensor_msgs::JointState &state, const std::string &controller="")
bool pushAndExecute (const trajectory_msgs::JointTrajectory &trajectory, const std::vector< std::string > &controllers)
bool pushAndExecute (const moveit_msgs::RobotTrajectory &trajectory, const std::vector< std::string > &controllers)
bool pushAndExecute (const sensor_msgs::JointState &state, const std::vector< std::string > &controllers)
void setAllowedExecutionDurationScaling (double scaling)
void setExecutionVelocityScaling (double scaling)
void stopExecution (bool auto_clear=true)
 Stop whatever executions are active, if any.
 TrajectoryExecutionManager (const robot_model::RobotModelConstPtr &kmodel)
 Load the controller manager plugin, start listening for events on a topic.
 TrajectoryExecutionManager (const robot_model::RobotModelConstPtr &kmodel, bool manage_controllers)
 Load the controller manager plugin, start listening for events on a topic.
moveit_controller_manager::ExecutionStatus waitForExecution ()
 Wait until the execution is complete. This applies for executions started by either execute() or pushAndExecute()
 ~TrajectoryExecutionManager ()
 Destructor. Cancels all running trajectories (if any)

Static Public Attributes

static const std::string EXECUTION_EVENT_TOPIC = "trajectory_execution_event"

Private Member Functions

bool checkControllerCombination (std::vector< std::string > &controllers, const std::set< std::string > &actuated_joints)
bool configure (TrajectoryExecutionContext &context, const moveit_msgs::RobotTrajectory &trajectory, const std::vector< std::string > &controllers)
void continuousExecutionThread ()
bool distributeTrajectory (const moveit_msgs::RobotTrajectory &trajectory, const std::vector< std::string > &controllers, std::vector< moveit_msgs::RobotTrajectory > &parts)
bool executePart (std::size_t part_index)
void executeThread (const ExecutionCompleteCallback &callback, const PathSegmentCompleteCallback &part_callback, bool auto_clear)
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)
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)
void initialize ()
void receiveEvent (const std_msgs::StringConstPtr &event)
void reloadControllerInformation ()
bool selectControllers (const std::set< std::string > &actuated_joints, const std::vector< std::string > &available_controllers, std::vector< std::string > &selected_controllers)
void stopExecutionInternal ()
void updateControllersState (const ros::Duration &age)
void updateControllerState (const std::string &controller, const ros::Duration &age)
void updateControllerState (ControllerInformation &ci, const ros::Duration &age)

Private Attributes

std::vector
< moveit_controller_manager::MoveItControllerHandlePtr
active_handles_
double allowed_execution_duration_scaling_
boost::condition_variable continuous_execution_condition_
boost::mutex continuous_execution_mutex_
std::deque
< TrajectoryExecutionContext * > 
continuous_execution_queue_
boost::scoped_ptr< boost::thread > continuous_execution_thread_
moveit_controller_manager::MoveItControllerManagerPtr controller_manager_
boost::scoped_ptr
< pluginlib::ClassLoader
< moveit_controller_manager::MoveItControllerManager > > 
controller_manager_loader_
int current_context_
ros::Subscriber event_topic_subscriber_
bool execution_complete_
boost::condition_variable execution_complete_condition_
bool execution_duration_monitoring_
boost::mutex execution_state_mutex_
boost::scoped_ptr< boost::thread > execution_thread_
double execution_velocity_scaling_
robot_model::RobotModelConstPtr kinematic_model_
std::map< std::string,
ControllerInformation
known_controllers_
moveit_controller_manager::ExecutionStatus last_execution_status_
bool manage_controllers_
ros::NodeHandle node_handle_
DynamicReconfigureImplreconfigure_impl_
ros::NodeHandle root_node_handle_
bool run_continuous_execution_thread_
bool stop_continuous_execution_
std::vector< ros::Timetime_index_
boost::mutex time_index_mutex_
std::vector
< TrajectoryExecutionContext * > 
trajectories_
bool verbose_

Detailed Description

Definition at line 56 of file trajectory_execution_manager.h.


Member Typedef Documentation

Definition of the function signature that is called when the execution of all the pushed trajectories completes. The status of the overall execution is passed as argument.

Definition at line 63 of file trajectory_execution_manager.h.

Definition of the function signature that is called when the execution of a pushed trajectory completes successfully.

Definition at line 66 of file trajectory_execution_manager.h.


Constructor & Destructor Documentation

Load the controller manager plugin, start listening for events on a topic.

Definition at line 74 of file trajectory_execution_manager.cpp.

Load the controller manager plugin, start listening for events on a topic.

Definition at line 82 of file trajectory_execution_manager.cpp.

Destructor. Cancels all running trajectories (if any)

Definition at line 88 of file trajectory_execution_manager.cpp.


Member Function Documentation

bool trajectory_execution_manager::TrajectoryExecutionManager::areControllersActive ( const std::vector< std::string > &  controllers)

Check if a set of controllers are active.

Definition at line 699 of file trajectory_execution_manager.cpp.

bool trajectory_execution_manager::TrajectoryExecutionManager::checkControllerCombination ( std::vector< std::string > &  controllers,
const std::set< std::string > &  actuated_joints 
) [private]

Definition at line 527 of file trajectory_execution_manager.cpp.

Clear the trajectories to execute.

Definition at line 993 of file trajectory_execution_manager.cpp.

bool trajectory_execution_manager::TrajectoryExecutionManager::configure ( TrajectoryExecutionContext context,
const moveit_msgs::RobotTrajectory &  trajectory,
const std::vector< std::string > &  controllers 
) [private]

Definition at line 826 of file trajectory_execution_manager.cpp.

Definition at line 326 of file trajectory_execution_manager.cpp.

bool trajectory_execution_manager::TrajectoryExecutionManager::distributeTrajectory ( const moveit_msgs::RobotTrajectory &  trajectory,
const std::vector< std::string > &  controllers,
std::vector< moveit_msgs::RobotTrajectory > &  parts 
) [private]

Definition at line 735 of file trajectory_execution_manager.cpp.

Enable or disable the monitoring of trajectory execution duration. If a controller takes longer than expected, the trajectory is canceled

Definition at line 158 of file trajectory_execution_manager.cpp.

Make sure a particular controller is active.

Note:
If manage_controllers_ is false and the controllers that happen to be active to not include the one specified as argument, this function fails.

Definition at line 1288 of file trajectory_execution_manager.cpp.

bool trajectory_execution_manager::TrajectoryExecutionManager::ensureActiveControllers ( const std::vector< std::string > &  controllers)

Make sure a particular set of controllers are active.

Note:
If manage_controllers_ is false and the controllers that happen to be active to not include the ones specified as argument, this function fails.

Definition at line 1293 of file trajectory_execution_manager.cpp.

Make sure the active controllers are such that trajectories that actuate joints in the specified group can be executed.

Note:
If manage_controllers_ is false and the controllers that happen to be active do not cover the joints in the group to be actuated, this function fails.

Definition at line 1265 of file trajectory_execution_manager.cpp.

Make sure the active controllers are such that trajectories that actuate joints in the specified set can be executed.

Note:
If manage_controllers_ is false and the controllers that happen to be active do not cover the joints to be actuated, this function fails.

Definition at line 1274 of file trajectory_execution_manager.cpp.

Start the execution of pushed trajectories; this does not wait for completion, but calls a callback when done.

Definition at line 961 of file trajectory_execution_manager.cpp.

void trajectory_execution_manager::TrajectoryExecutionManager::execute ( const ExecutionCompleteCallback callback,
const PathSegmentCompleteCallback part_callback,
bool  auto_clear = true 
)

Start the execution of pushed trajectories; this does not wait for completion, but calls a callback when done. A callback is also called for every trajectory part that completes successfully.

Definition at line 966 of file trajectory_execution_manager.cpp.

This is a blocking call for the execution of the passed in trajectories. This just calls execute() and waitForExecution()

Definition at line 903 of file trajectory_execution_manager.cpp.

Definition at line 1056 of file trajectory_execution_manager.cpp.

void trajectory_execution_manager::TrajectoryExecutionManager::executeThread ( const ExecutionCompleteCallback callback,
const PathSegmentCompleteCallback part_callback,
bool  auto_clear 
) [private]

Definition at line 1013 of file trajectory_execution_manager.cpp.

bool trajectory_execution_manager::TrajectoryExecutionManager::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 
) [private]

Definition at line 616 of file trajectory_execution_manager.cpp.

void trajectory_execution_manager::TrajectoryExecutionManager::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 
) [private]

Definition at line 552 of file trajectory_execution_manager.cpp.

Get the instance of the controller manager used (this is the plugin instance loaded)

Definition at line 178 of file trajectory_execution_manager.cpp.

Get the state that the robot is expected to be at, given current time, after execute() has been called. The return value is a pair of two index values: first = the index of the trajectory to be executed (in the order push() was called), second = the index of the point within that trajectory. Values of -1 are returned when there is no trajectory being executed, or if the trajectory was passed using pushAndExecute().

Definition at line 1243 of file trajectory_execution_manager.cpp.

Return the controller status for the last attempted execution.

Definition at line 1260 of file trajectory_execution_manager.cpp.

Get the trajectories to be executed.

Definition at line 1255 of file trajectory_execution_manager.cpp.

Definition at line 95 of file trajectory_execution_manager.cpp.

Check if a controller is active.

Definition at line 694 of file trajectory_execution_manager.cpp.

If this function returns true, then this instance of the manager is allowed to load/unload/switch controllers.

Definition at line 173 of file trajectory_execution_manager.cpp.

Execute a named event (e.g., 'stop')

Definition at line 183 of file trajectory_execution_manager.cpp.

bool trajectory_execution_manager::TrajectoryExecutionManager::push ( const moveit_msgs::RobotTrajectory &  trajectory,
const std::string &  controller = "" 
)

Add a trajectory for future execution. Optionally specify a controller to use for the trajectory. If no controller is specified, a default is used.

Definition at line 197 of file trajectory_execution_manager.cpp.

bool trajectory_execution_manager::TrajectoryExecutionManager::push ( const trajectory_msgs::JointTrajectory &  trajectory,
const std::string &  controller = "" 
)

Add a trajectory for future execution. Optionally specify a controller to use for the trajectory. If no controller is specified, a default is used.

Definition at line 205 of file trajectory_execution_manager.cpp.

bool trajectory_execution_manager::TrajectoryExecutionManager::push ( const trajectory_msgs::JointTrajectory &  trajectory,
const std::vector< std::string > &  controllers 
)

Add a trajectory for future execution. Optionally specify a set of controllers to consider using for the trajectory. Multiple controllers can be used simultaneously to execute the different parts of the trajectory. If multiple controllers can be used, preference is given to the already loaded ones. If no controller is specified, a default is used.

Definition at line 213 of file trajectory_execution_manager.cpp.

bool trajectory_execution_manager::TrajectoryExecutionManager::push ( const moveit_msgs::RobotTrajectory &  trajectory,
const std::vector< std::string > &  controllers 
)

Add a trajectory for future execution. Optionally specify a set of controllers to consider using for the trajectory. Multiple controllers can be used simultaneously to execute the different parts of the trajectory. If multiple controllers can be used, preference is given to the already loaded ones. If no controller is specified, a default is used.

Definition at line 220 of file trajectory_execution_manager.cpp.

bool trajectory_execution_manager::TrajectoryExecutionManager::pushAndExecute ( const moveit_msgs::RobotTrajectory &  trajectory,
const std::string &  controller = "" 
)

Add a trajectory for immediate execution. Optionally specify a controller to use for the trajectory. If no controller is specified, a default is used. This call is non-blocking.

Definition at line 254 of file trajectory_execution_manager.cpp.

bool trajectory_execution_manager::TrajectoryExecutionManager::pushAndExecute ( const trajectory_msgs::JointTrajectory &  trajectory,
const std::string &  controller = "" 
)

Add a trajectory for immediate execution. Optionally specify a controller to use for the trajectory. If no controller is specified, a default is used. This call is non-blocking.

Definition at line 262 of file trajectory_execution_manager.cpp.

bool trajectory_execution_manager::TrajectoryExecutionManager::pushAndExecute ( const sensor_msgs::JointState &  state,
const std::string &  controller = "" 
)

Add a trajectory that consists of a single state for immediate execution. Optionally specify a controller to use for the trajectory. If no controller is specified, a default is used. This call is non-blocking.

Definition at line 270 of file trajectory_execution_manager.cpp.

bool trajectory_execution_manager::TrajectoryExecutionManager::pushAndExecute ( const trajectory_msgs::JointTrajectory &  trajectory,
const std::vector< std::string > &  controllers 
)

Add a trajectory for immediate execution. Optionally specify a set of controllers to consider using for the trajectory. Multiple controllers can be used simultaneously to execute the different parts of the trajectory. If multiple controllers can be used, preference is given to the already loaded ones. If no controller is specified, a default is used. This call is non-blocking.

Definition at line 278 of file trajectory_execution_manager.cpp.

bool trajectory_execution_manager::TrajectoryExecutionManager::pushAndExecute ( const moveit_msgs::RobotTrajectory &  trajectory,
const std::vector< std::string > &  controllers 
)

Add a trajectory for immediate execution. Optionally specify a set of controllers to consider using for the trajectory. Multiple controllers can be used simultaneously to execute the different parts of the trajectory. If multiple controllers can be used, preference is given to the already loaded ones. If no controller is specified, a default is used. This call is non-blocking.

Definition at line 297 of file trajectory_execution_manager.cpp.

bool trajectory_execution_manager::TrajectoryExecutionManager::pushAndExecute ( const sensor_msgs::JointState &  state,
const std::vector< std::string > &  controllers 
)

Add a trajectory that consists of a single state for immediate execution. Optionally specify a set of controllers to consider using for the trajectory. Multiple controllers can be used simultaneously to execute the different parts of the trajectory. If multiple controllers can be used, preference is given to the already loaded ones. If no controller is specified, a default is used. This call is non-blocking.

Definition at line 285 of file trajectory_execution_manager.cpp.

void trajectory_execution_manager::TrajectoryExecutionManager::receiveEvent ( const std_msgs::StringConstPtr &  event) [private]

Definition at line 191 of file trajectory_execution_manager.cpp.

Definition at line 461 of file trajectory_execution_manager.cpp.

bool trajectory_execution_manager::TrajectoryExecutionManager::selectControllers ( const std::set< std::string > &  actuated_joints,
const std::vector< std::string > &  available_controllers,
std::vector< std::string > &  selected_controllers 
) [private]

Definition at line 711 of file trajectory_execution_manager.cpp.

When determining the expected duration of a trajectory, this multiplicative factor is applied to get the allowed duration of execution

Definition at line 163 of file trajectory_execution_manager.cpp.

Before sending a trajectory to a controller, scale the velocities by the factor specified. By default, this is 1.0

Definition at line 168 of file trajectory_execution_manager.cpp.

Stop whatever executions are active, if any.

Definition at line 923 of file trajectory_execution_manager.cpp.

Definition at line 909 of file trajectory_execution_manager.cpp.

Definition at line 521 of file trajectory_execution_manager.cpp.

void trajectory_execution_manager::TrajectoryExecutionManager::updateControllerState ( const std::string &  controller,
const ros::Duration age 
) [private]

Definition at line 495 of file trajectory_execution_manager.cpp.

Definition at line 504 of file trajectory_execution_manager.cpp.

Wait until the execution is complete. This applies for executions started by either execute() or pushAndExecute()

Definition at line 974 of file trajectory_execution_manager.cpp.


Member Data Documentation

Definition at line 269 of file trajectory_execution_manager.h.

Definition at line 289 of file trajectory_execution_manager.h.

Definition at line 263 of file trajectory_execution_manager.h.

Definition at line 261 of file trajectory_execution_manager.h.

Definition at line 278 of file trajectory_execution_manager.h.

Definition at line 258 of file trajectory_execution_manager.h.

Definition at line 281 of file trajectory_execution_manager.h.

Definition at line 280 of file trajectory_execution_manager.h.

Definition at line 270 of file trajectory_execution_manager.h.

Definition at line 249 of file trajectory_execution_manager.h.

Definition at line 273 of file trajectory_execution_manager.h.

Definition at line 266 of file trajectory_execution_manager.h.

Definition at line 288 of file trajectory_execution_manager.h.

const std::string trajectory_execution_manager::TrajectoryExecutionManager::EXECUTION_EVENT_TOPIC = "trajectory_execution_event" [static]

Definition at line 60 of file trajectory_execution_manager.h.

Definition at line 260 of file trajectory_execution_manager.h.

Definition at line 255 of file trajectory_execution_manager.h.

Definition at line 290 of file trajectory_execution_manager.h.

Definition at line 246 of file trajectory_execution_manager.h.

Definition at line 251 of file trajectory_execution_manager.h.

Definition at line 268 of file trajectory_execution_manager.h.

Definition at line 252 of file trajectory_execution_manager.h.

Definition at line 247 of file trajectory_execution_manager.h.

Definition at line 285 of file trajectory_execution_manager.h.

Definition at line 248 of file trajectory_execution_manager.h.

Definition at line 276 of file trajectory_execution_manager.h.

Definition at line 275 of file trajectory_execution_manager.h.

Definition at line 271 of file trajectory_execution_manager.h.

Definition at line 272 of file trajectory_execution_manager.h.

Definition at line 277 of file trajectory_execution_manager.h.

Definition at line 283 of file trajectory_execution_manager.h.


The documentation for this class was generated from the following files:


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Mon Oct 6 2014 02:31:40