moveit2
The MoveIt Motion Planning Framework for ROS 2.
Classes | Public Types | Public Member Functions | Static Public Attributes | List of all members
trajectory_execution_manager::TrajectoryExecutionManager Class Reference

#include <trajectory_execution_manager.h>

Classes

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

Public Types

typedef std::function< void(const moveit_controller_manager::ExecutionStatus &)> ExecutionCompleteCallback
 
using PathSegmentCompleteCallback = std::function< void(std::size_t)>
 

Public Member Functions

 TrajectoryExecutionManager (const rclcpp::Node::SharedPtr &node, const moveit::core::RobotModelConstPtr &robot_model, const planning_scene_monitor::CurrentStateMonitorPtr &csm)
 Load the controller manager plugin, start listening for events on a topic. More...
 
 TrajectoryExecutionManager (const rclcpp::Node::SharedPtr &node, const moveit::core::RobotModelConstPtr &robot_model, const planning_scene_monitor::CurrentStateMonitorPtr &csm, bool manage_controllers)
 Load the controller manager plugin, start listening for events on a topic. More...
 
 ~TrajectoryExecutionManager ()
 Destructor. Cancels all running trajectories (if any) More...
 
bool isManagingControllers () const
 If this function returns true, then this instance of the manager is allowed to load/unload/switch controllers. More...
 
const moveit_controller_manager::MoveItControllerManagerPtr & getControllerManager () const
 Get the instance of the controller manager used (this is the plugin instance loaded) More...
 
void processEvent (const std::string &event)
 Execute a named event (e.g., 'stop') More...
 
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. More...
 
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. More...
 
bool ensureActiveController (const std::string &controller)
 Make sure a particular controller is active. More...
 
bool ensureActiveControllers (const std::vector< std::string > &controllers)
 Make sure a particular set of controllers are active. More...
 
bool isControllerActive (const std::string &controller)
 Check if a controller is active. More...
 
bool areControllersActive (const std::vector< std::string > &controllers)
 Check if a set of controllers is active. More...
 
bool push (const moveit_msgs::msg::RobotTrajectory &trajectory, const std::string &controller="")
 
bool push (const trajectory_msgs::msg::JointTrajectory &trajectory, const std::string &controller="")
 
bool push (const trajectory_msgs::msg::JointTrajectory &trajectory, const std::vector< std::string > &controllers)
 
bool push (const moveit_msgs::msg::RobotTrajectory &trajectory, const std::vector< std::string > &controllers)
 
const std::vector< TrajectoryExecutionContext * > & getTrajectories () const
 Get the trajectories to be executed. More...
 
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. More...
 
void execute (const ExecutionCompleteCallback &callback, const PathSegmentCompleteCallback &part_callback, bool auto_clear=true)
 
moveit_controller_manager::ExecutionStatus executeAndWait (bool auto_clear=true)
 
moveit_controller_manager::ExecutionStatus waitForExecution ()
 
std::pair< int, int > getCurrentExpectedTrajectoryIndex () const
 
moveit_controller_manager::ExecutionStatus getLastExecutionStatus () const
 Return the controller status for the last attempted execution. More...
 
void stopExecution (bool auto_clear=true)
 Stop whatever executions are active, if any. More...
 
void clear ()
 Clear the trajectories to execute. More...
 
void enableExecutionDurationMonitoring (bool flag)
 
void setAllowedExecutionDurationScaling (double scaling)
 
void setAllowedGoalDurationMargin (double margin)
 
void setExecutionVelocityScaling (double scaling)
 
void setAllowedStartTolerance (double tolerance)
 Set joint-value tolerance for validating trajectory's start point against current robot state. More...
 
void setWaitForTrajectoryCompletion (bool flag)
 Enable or disable waiting for trajectory completion. More...
 
rclcpp::Node::SharedPtr getControllerManagerNode ()
 

Static Public Attributes

static const std::string EXECUTION_EVENT_TOPIC = "trajectory_execution_event"
 

Detailed Description

Definition at line 62 of file trajectory_execution_manager.h.

Member Typedef Documentation

◆ 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

Definition at line 69 of file trajectory_execution_manager.h.

◆ PathSegmentCompleteCallback

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

Definition at line 73 of file trajectory_execution_manager.h.

Constructor & Destructor Documentation

◆ TrajectoryExecutionManager() [1/2]

trajectory_execution_manager::TrajectoryExecutionManager::TrajectoryExecutionManager ( const rclcpp::Node::SharedPtr &  node,
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 at line 55 of file trajectory_execution_manager.cpp.

◆ TrajectoryExecutionManager() [2/2]

trajectory_execution_manager::TrajectoryExecutionManager::TrajectoryExecutionManager ( const rclcpp::Node::SharedPtr &  node,
const moveit::core::RobotModelConstPtr &  robot_model,
const planning_scene_monitor::CurrentStateMonitorPtr &  csm,
bool  manage_controllers 
)

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

Definition at line 65 of file trajectory_execution_manager.cpp.

◆ ~TrajectoryExecutionManager()

trajectory_execution_manager::TrajectoryExecutionManager::~TrajectoryExecutionManager ( )

Destructor. Cancels all running trajectories (if any)

Definition at line 78 of file trajectory_execution_manager.cpp.

Here is the call graph for this function:

Member Function Documentation

◆ areControllersActive()

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

Check if a set of controllers is active.

Definition at line 652 of file trajectory_execution_manager.cpp.

Here is the caller graph for this function:

◆ clear()

void trajectory_execution_manager::TrajectoryExecutionManager::clear ( )

Clear the trajectories to execute.

Definition at line 1164 of file trajectory_execution_manager.cpp.

Here is the caller graph for this function:

◆ enableExecutionDurationMonitoring()

void trajectory_execution_manager::TrajectoryExecutionManager::enableExecutionDurationMonitoring ( bool  flag)

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

Definition at line 253 of file trajectory_execution_manager.cpp.

Here is the caller graph for this function:

◆ ensureActiveController()

bool trajectory_execution_manager::TrajectoryExecutionManager::ensureActiveController ( const std::string &  controller)

Make sure a particular controller is active.

Note
If the 'moveit_manage_controllers' parameter is false and the controllers that happen to be active do not include the one specified as argument, this function fails.

Definition at line 1581 of file trajectory_execution_manager.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ ensureActiveControllers()

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

Make sure a particular set of controllers are active.

Note
If the 'moveit_manage_controllers' parameter is false and the controllers that happen to be active do not include the ones specified as argument, this function fails.

Definition at line 1586 of file trajectory_execution_manager.cpp.

Here is the caller graph for this function:

◆ ensureActiveControllersForGroup()

bool trajectory_execution_manager::TrajectoryExecutionManager::ensureActiveControllersForGroup ( const std::string &  group)

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

Note
If the 'moveit_manage_controllers' parameter 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 1539 of file trajectory_execution_manager.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ ensureActiveControllersForJoints()

bool trajectory_execution_manager::TrajectoryExecutionManager::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.

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

Definition at line 1552 of file trajectory_execution_manager.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ execute() [1/2]

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 1123 of file trajectory_execution_manager.cpp.

Here is the call graph for this function:

◆ execute() [2/2]

void trajectory_execution_manager::TrajectoryExecutionManager::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.

Definition at line 1118 of file trajectory_execution_manager.cpp.

Here is the caller graph for this function:

◆ executeAndWait()

moveit_controller_manager::ExecutionStatus trajectory_execution_manager::TrajectoryExecutionManager::executeAndWait ( bool  auto_clear = true)

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

Definition at line 1051 of file trajectory_execution_manager.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getControllerManager()

const moveit_controller_manager::MoveItControllerManagerPtr & trajectory_execution_manager::TrajectoryExecutionManager::getControllerManager ( ) const

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

Definition at line 288 of file trajectory_execution_manager.cpp.

◆ getControllerManagerNode()

rclcpp::Node::SharedPtr trajectory_execution_manager::TrajectoryExecutionManager::getControllerManagerNode ( )
inline

Definition at line 214 of file trajectory_execution_manager.h.

◆ getCurrentExpectedTrajectoryIndex()

std::pair< int, int > trajectory_execution_manager::TrajectoryExecutionManager::getCurrentExpectedTrajectoryIndex ( ) const

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 1515 of file trajectory_execution_manager.cpp.

◆ getLastExecutionStatus()

moveit_controller_manager::ExecutionStatus trajectory_execution_manager::TrajectoryExecutionManager::getLastExecutionStatus ( ) const

Return the controller status for the last attempted execution.

Definition at line 1534 of file trajectory_execution_manager.cpp.

Here is the caller graph for this function:

◆ getTrajectories()

const std::vector< TrajectoryExecutionManager::TrajectoryExecutionContext * > & trajectory_execution_manager::TrajectoryExecutionManager::getTrajectories ( ) const

Get the trajectories to be executed.

Definition at line 1529 of file trajectory_execution_manager.cpp.

◆ isControllerActive()

bool trajectory_execution_manager::TrajectoryExecutionManager::isControllerActive ( const std::string &  controller)

Check if a controller is active.

Definition at line 647 of file trajectory_execution_manager.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ isManagingControllers()

bool trajectory_execution_manager::TrajectoryExecutionManager::isManagingControllers ( ) const

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

Definition at line 283 of file trajectory_execution_manager.cpp.

Here is the caller graph for this function:

◆ processEvent()

void trajectory_execution_manager::TrajectoryExecutionManager::processEvent ( const std::string &  event)

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

Definition at line 293 of file trajectory_execution_manager.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ push() [1/4]

bool trajectory_execution_manager::TrajectoryExecutionManager::push ( const moveit_msgs::msg::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 311 of file trajectory_execution_manager.cpp.

Here is the caller graph for this function:

◆ push() [2/4]

bool trajectory_execution_manager::TrajectoryExecutionManager::push ( const moveit_msgs::msg::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 344 of file trajectory_execution_manager.cpp.

◆ push() [3/4]

bool trajectory_execution_manager::TrajectoryExecutionManager::push ( const trajectory_msgs::msg::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 323 of file trajectory_execution_manager.cpp.

Here is the call graph for this function:

◆ push() [4/4]

bool trajectory_execution_manager::TrajectoryExecutionManager::push ( const trajectory_msgs::msg::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 336 of file trajectory_execution_manager.cpp.

Here is the call graph for this function:

◆ setAllowedExecutionDurationScaling()

void trajectory_execution_manager::TrajectoryExecutionManager::setAllowedExecutionDurationScaling ( double  scaling)

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

Definition at line 258 of file trajectory_execution_manager.cpp.

Here is the caller graph for this function:

◆ setAllowedGoalDurationMargin()

void trajectory_execution_manager::TrajectoryExecutionManager::setAllowedGoalDurationMargin ( double  margin)

When determining the expected duration of a trajectory, this multiplicative factor is applied to allow more than the expected execution time before triggering trajectory cancel

Definition at line 263 of file trajectory_execution_manager.cpp.

Here is the caller graph for this function:

◆ setAllowedStartTolerance()

void trajectory_execution_manager::TrajectoryExecutionManager::setAllowedStartTolerance ( double  tolerance)

Set joint-value tolerance for validating trajectory's start point against current robot state.

Definition at line 273 of file trajectory_execution_manager.cpp.

Here is the caller graph for this function:

◆ setExecutionVelocityScaling()

void trajectory_execution_manager::TrajectoryExecutionManager::setExecutionVelocityScaling ( double  scaling)

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

Definition at line 268 of file trajectory_execution_manager.cpp.

Here is the caller graph for this function:

◆ setWaitForTrajectoryCompletion()

void trajectory_execution_manager::TrajectoryExecutionManager::setWaitForTrajectoryCompletion ( bool  flag)

Enable or disable waiting for trajectory completion.

Definition at line 278 of file trajectory_execution_manager.cpp.

Here is the caller graph for this function:

◆ stopExecution()

void trajectory_execution_manager::TrajectoryExecutionManager::stopExecution ( bool  auto_clear = true)

Stop whatever executions are active, if any.

Definition at line 1073 of file trajectory_execution_manager.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ waitForExecution()

moveit_controller_manager::ExecutionStatus trajectory_execution_manager::TrajectoryExecutionManager::waitForExecution ( )

Wait until the execution is complete. This only works for executions started by execute(). If you call this after pushAndExecute(), it will immediately stop execution.

Definition at line 1150 of file trajectory_execution_manager.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ EXECUTION_EVENT_TOPIC

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

Definition at line 65 of file trajectory_execution_manager.h.


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