moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#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. | |
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. | |
~TrajectoryExecutionManager () | |
Destructor. Cancels all running trajectories (if any) | |
bool | isManagingControllers () const |
If this function returns true, then this instance of the manager is allowed to load/unload/switch controllers. | |
const moveit_controller_manager::MoveItControllerManagerPtr & | getControllerManager () const |
Get the instance of the controller manager used (this is the plugin instance loaded) | |
void | processEvent (const std::string &event) |
Execute a named event (e.g., 'stop') | |
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. | |
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 | isControllerActive (const std::string &controller) |
Check if a controller is active. | |
bool | areControllersActive (const std::vector< std::string > &controllers) |
Check if a set of controllers is active. | |
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. | |
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) |
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. | |
void | stopExecution (bool auto_clear=true) |
Stop whatever executions are active, if any. | |
void | clear () |
Clear the trajectories to execute. | |
void | enableExecutionDurationMonitoring (bool flag) |
bool | executionDurationMonitoring () const |
Get the current status of the monitoring of trajectory execution duration. | |
void | setAllowedExecutionDurationScaling (double scaling) |
double | allowedExecutionDurationScaling () const |
Get the current scaling of the duration of a trajectory to get the allowed duration of execution. | |
void | setAllowedGoalDurationMargin (double margin) |
double | allowedGoalDurationMargin () const |
Get the current margin of the duration of a trajectory to get the allowed duration of execution. | |
void | setExecutionVelocityScaling (double scaling) |
double | executionVelocityScaling () const |
Get the current scaling of the execution velocities. | |
void | setAllowedStartTolerance (double tolerance) |
Set joint-value tolerance for validating trajectory's start point against current robot state. | |
double | allowedStartTolerance () const |
Get the current joint-value for validating trajectory's start point against current robot state. | |
void | setWaitForTrajectoryCompletion (bool flag) |
Enable or disable waiting for trajectory completion. | |
bool | waitForTrajectoryCompletion () const |
Get the current state of waiting for the trajectory being completed. | |
rclcpp::Node::SharedPtr | getControllerManagerNode () |
Static Public Attributes | |
static const std::string | EXECUTION_EVENT_TOPIC = "trajectory_execution_event" |
Definition at line 62 of file trajectory_execution_manager.h.
typedef std::function<void(const moveit_controller_manager::ExecutionStatus&)> trajectory_execution_manager::TrajectoryExecutionManager::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.
using trajectory_execution_manager::TrajectoryExecutionManager::PathSegmentCompleteCallback = std::function<void(std::size_t)> |
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.
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 58 of file trajectory_execution_manager.cpp.
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 71 of file trajectory_execution_manager.cpp.
trajectory_execution_manager::TrajectoryExecutionManager::~TrajectoryExecutionManager | ( | ) |
Destructor. Cancels all running trajectories (if any)
Definition at line 84 of file trajectory_execution_manager.cpp.
double trajectory_execution_manager::TrajectoryExecutionManager::allowedExecutionDurationScaling | ( | ) | const |
Get the current scaling of the duration of a trajectory to get the allowed duration of execution.
Definition at line 277 of file trajectory_execution_manager.cpp.
double trajectory_execution_manager::TrajectoryExecutionManager::allowedGoalDurationMargin | ( | ) | const |
Get the current margin of the duration of a trajectory to get the allowed duration of execution.
Definition at line 287 of file trajectory_execution_manager.cpp.
double trajectory_execution_manager::TrajectoryExecutionManager::allowedStartTolerance | ( | ) | const |
Get the current joint-value for validating trajectory's start point against current robot state.
Definition at line 307 of file trajectory_execution_manager.cpp.
bool trajectory_execution_manager::TrajectoryExecutionManager::areControllersActive | ( | const std::vector< std::string > & | controllers | ) |
Check if a set of controllers is active.
Definition at line 728 of file trajectory_execution_manager.cpp.
void trajectory_execution_manager::TrajectoryExecutionManager::clear | ( | ) |
Clear the trajectories to execute.
Definition at line 1270 of file trajectory_execution_manager.cpp.
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 262 of file trajectory_execution_manager.cpp.
bool trajectory_execution_manager::TrajectoryExecutionManager::ensureActiveController | ( | const std::string & | controller | ) |
Make sure a particular controller is active.
Definition at line 1688 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.
Definition at line 1693 of file trajectory_execution_manager.cpp.
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.
Definition at line 1646 of file trajectory_execution_manager.cpp.
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.
Definition at line 1659 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 1229 of file trajectory_execution_manager.cpp.
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 1224 of file trajectory_execution_manager.cpp.
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 1157 of file trajectory_execution_manager.cpp.
bool trajectory_execution_manager::TrajectoryExecutionManager::executionDurationMonitoring | ( | ) | const |
Get the current status of the monitoring of trajectory execution duration.
Definition at line 267 of file trajectory_execution_manager.cpp.
double trajectory_execution_manager::TrajectoryExecutionManager::executionVelocityScaling | ( | ) | const |
Get the current scaling of the execution velocities.
Definition at line 297 of file trajectory_execution_manager.cpp.
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 327 of file trajectory_execution_manager.cpp.
|
inline |
Definition at line 232 of file trajectory_execution_manager.h.
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 1622 of file trajectory_execution_manager.cpp.
moveit_controller_manager::ExecutionStatus trajectory_execution_manager::TrajectoryExecutionManager::getLastExecutionStatus | ( | ) | const |
Return the controller status for the last attempted execution.
Definition at line 1641 of file trajectory_execution_manager.cpp.
const std::vector< TrajectoryExecutionManager::TrajectoryExecutionContext * > & trajectory_execution_manager::TrajectoryExecutionManager::getTrajectories | ( | ) | const |
Get the trajectories to be executed.
Definition at line 1636 of file trajectory_execution_manager.cpp.
bool trajectory_execution_manager::TrajectoryExecutionManager::isControllerActive | ( | const std::string & | controller | ) |
Check if a controller is active.
Definition at line 723 of file trajectory_execution_manager.cpp.
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 322 of file trajectory_execution_manager.cpp.
void trajectory_execution_manager::TrajectoryExecutionManager::processEvent | ( | const std::string & | event | ) |
Execute a named event (e.g., 'stop')
Definition at line 332 of file trajectory_execution_manager.cpp.
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 350 of file trajectory_execution_manager.cpp.
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 383 of file trajectory_execution_manager.cpp.
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 362 of file trajectory_execution_manager.cpp.
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 375 of file trajectory_execution_manager.cpp.
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 272 of file trajectory_execution_manager.cpp.
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 282 of file trajectory_execution_manager.cpp.
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 302 of file trajectory_execution_manager.cpp.
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 292 of file trajectory_execution_manager.cpp.
void trajectory_execution_manager::TrajectoryExecutionManager::setWaitForTrajectoryCompletion | ( | bool | flag | ) |
Enable or disable waiting for trajectory completion.
Definition at line 312 of file trajectory_execution_manager.cpp.
void trajectory_execution_manager::TrajectoryExecutionManager::stopExecution | ( | bool | auto_clear = true | ) |
Stop whatever executions are active, if any.
Definition at line 1179 of file trajectory_execution_manager.cpp.
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 1256 of file trajectory_execution_manager.cpp.
bool trajectory_execution_manager::TrajectoryExecutionManager::waitForTrajectoryCompletion | ( | ) | const |
Get the current state of waiting for the trajectory being completed.
Definition at line 317 of file trajectory_execution_manager.cpp.
|
static |
Definition at line 65 of file trajectory_execution_manager.h.