Classes | Public Types | Public Member Functions | Static Public Attributes | Private Member Functions | Private Attributes | List of all members
trajectory_execution_manager::TrajectoryExecutionManager Class Reference

#include <trajectory_execution_manager.h>

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
 
using PathSegmentCompleteCallback = boost::function< void(std::size_t)>
 

Public Member Functions

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

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)
 
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)
 
double getJointAllowedStartTolerance (std::string const &jointName) const
 
void initialize ()
 
void loadControllerParams ()
 
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)
 
void updateJointsAllowedStartTolerance ()
 
bool validate (const TrajectoryExecutionContext &context) const
 Validate first point of trajectory matches current robot state. More...
 
bool waitForRobotToStop (const TrajectoryExecutionContext &context, double wait_time=1.0)
 

Private Attributes

std::vector< moveit_controller_manager::MoveItControllerHandlePtr > active_handles_
 
double allowed_execution_duration_scaling_
 
double allowed_goal_duration_margin_
 
double allowed_start_tolerance_
 
std::map< std::string, double > controller_allowed_execution_duration_scaling_
 
std::map< std::string, double > controller_allowed_goal_duration_margin_
 
moveit_controller_manager::MoveItControllerManagerPtr controller_manager_
 
std::unique_ptr< pluginlib::ClassLoader< moveit_controller_manager::MoveItControllerManager > > controller_manager_loader_
 
planning_scene_monitor::CurrentStateMonitorPtr csm_
 
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_
 
std::unique_ptr< boost::thread > execution_thread_
 
boost::mutex execution_thread_mutex_
 
double execution_velocity_scaling_
 
std::map< std::string, double > joints_allowed_start_tolerance_
 
std::map< std::string, ControllerInformationknown_controllers_
 
moveit_controller_manager::ExecutionStatus last_execution_status_
 
bool manage_controllers_
 
ros::NodeHandle node_handle_
 
DynamicReconfigureImplreconfigure_impl_
 
moveit::core::RobotModelConstPtr robot_model_
 
ros::NodeHandle root_node_handle_
 
std::vector< ros::Timetime_index_
 
boost::mutex time_index_mutex_
 
std::vector< TrajectoryExecutionContext * > trajectories_
 
bool verbose_
 
bool wait_for_trajectory_completion_
 

Detailed Description

Definition at line 91 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 98 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 102 of file trajectory_execution_manager.h.

Constructor & Destructor Documentation

◆ TrajectoryExecutionManager() [1/2]

trajectory_execution_manager::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 at line 85 of file trajectory_execution_manager.cpp.

◆ TrajectoryExecutionManager() [2/2]

trajectory_execution_manager::TrajectoryExecutionManager::TrajectoryExecutionManager ( 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 95 of file trajectory_execution_manager.cpp.

◆ ~TrajectoryExecutionManager()

trajectory_execution_manager::TrajectoryExecutionManager::~TrajectoryExecutionManager ( )

Destructor. Cancels all running trajectories (if any)

Definition at line 103 of file trajectory_execution_manager.cpp.

Member Function Documentation

◆ areControllersActive()

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

Check if a set of controllers are active.

Definition at line 547 of file trajectory_execution_manager.cpp.

◆ checkControllerCombination()

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

Definition at line 367 of file trajectory_execution_manager.cpp.

◆ clear()

void trajectory_execution_manager::TrajectoryExecutionManager::clear ( )

Clear the trajectories to execute.

Definition at line 1045 of file trajectory_execution_manager.cpp.

◆ configure()

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

Definition at line 822 of file trajectory_execution_manager.cpp.

◆ distributeTrajectory()

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

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

◆ ensureActiveController()

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

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

◆ ensureActiveControllers()

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

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

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

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

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

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

◆ executePart()

bool trajectory_execution_manager::TrajectoryExecutionManager::executePart ( std::size_t  part_index)
private

Definition at line 1110 of file trajectory_execution_manager.cpp.

◆ executeThread()

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

Definition at line 1057 of file trajectory_execution_manager.cpp.

◆ findControllers()

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

◆ generateControllerCombination()

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

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

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

◆ getJointAllowedStartTolerance()

double trajectory_execution_manager::TrajectoryExecutionManager::getJointAllowedStartTolerance ( std::string const &  jointName) const
private

Definition at line 1567 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 1403 of file trajectory_execution_manager.cpp.

◆ getTrajectories()

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

Get the trajectories to be executed.

Definition at line 1398 of file trajectory_execution_manager.cpp.

◆ initialize()

void trajectory_execution_manager::TrajectoryExecutionManager::initialize ( )
private

Definition at line 109 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 542 of file trajectory_execution_manager.cpp.

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

◆ loadControllerParams()

void trajectory_execution_manager::TrajectoryExecutionManager::loadControllerParams ( )
private

Definition at line 1545 of file trajectory_execution_manager.cpp.

◆ processEvent()

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

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

Definition at line 228 of file trajectory_execution_manager.cpp.

◆ push() [1/4]

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

◆ push() [2/4]

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

◆ push() [3/4]

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

◆ push() [4/4]

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

◆ receiveEvent()

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

Definition at line 236 of file trajectory_execution_manager.cpp.

◆ reloadControllerInformation()

void trajectory_execution_manager::TrajectoryExecutionManager::reloadControllerInformation ( )
private

Definition at line 301 of file trajectory_execution_manager.cpp.

◆ selectControllers()

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

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

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

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

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

◆ setWaitForTrajectoryCompletion()

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

Enable or disable waiting for trajectory completion.

Definition at line 213 of file trajectory_execution_manager.cpp.

◆ stopExecution()

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

Stop whatever executions are active, if any.

Definition at line 952 of file trajectory_execution_manager.cpp.

◆ stopExecutionInternal()

void trajectory_execution_manager::TrajectoryExecutionManager::stopExecutionInternal ( )
private

Definition at line 938 of file trajectory_execution_manager.cpp.

◆ updateControllersState()

void trajectory_execution_manager::TrajectoryExecutionManager::updateControllersState ( const ros::Duration age)
private

Definition at line 361 of file trajectory_execution_manager.cpp.

◆ updateControllerState() [1/2]

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

Definition at line 336 of file trajectory_execution_manager.cpp.

◆ updateControllerState() [2/2]

void trajectory_execution_manager::TrajectoryExecutionManager::updateControllerState ( ControllerInformation ci,
const ros::Duration age 
)
private

Definition at line 345 of file trajectory_execution_manager.cpp.

◆ updateJointsAllowedStartTolerance()

void trajectory_execution_manager::TrajectoryExecutionManager::updateJointsAllowedStartTolerance ( )
private

Definition at line 1574 of file trajectory_execution_manager.cpp.

◆ validate()

bool trajectory_execution_manager::TrajectoryExecutionManager::validate ( const TrajectoryExecutionContext context) const
private

Validate first point of trajectory matches current robot state.

Definition at line 721 of file trajectory_execution_manager.cpp.

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

◆ waitForRobotToStop()

bool trajectory_execution_manager::TrajectoryExecutionManager::waitForRobotToStop ( const TrajectoryExecutionContext context,
double  wait_time = 1.0 
)
private

Definition at line 1324 of file trajectory_execution_manager.cpp.

Member Data Documentation

◆ active_handles_

std::vector<moveit_controller_manager::MoveItControllerHandlePtr> trajectory_execution_manager::TrajectoryExecutionManager::active_handles_
private

Definition at line 322 of file trajectory_execution_manager.h.

◆ allowed_execution_duration_scaling_

double trajectory_execution_manager::TrajectoryExecutionManager::allowed_execution_duration_scaling_
private

Definition at line 340 of file trajectory_execution_manager.h.

◆ allowed_goal_duration_margin_

double trajectory_execution_manager::TrajectoryExecutionManager::allowed_goal_duration_margin_
private

Definition at line 341 of file trajectory_execution_manager.h.

◆ allowed_start_tolerance_

double trajectory_execution_manager::TrajectoryExecutionManager::allowed_start_tolerance_
private

Definition at line 347 of file trajectory_execution_manager.h.

◆ controller_allowed_execution_duration_scaling_

std::map<std::string, double> trajectory_execution_manager::TrajectoryExecutionManager::controller_allowed_execution_duration_scaling_
private

Definition at line 344 of file trajectory_execution_manager.h.

◆ controller_allowed_goal_duration_margin_

std::map<std::string, double> trajectory_execution_manager::TrajectoryExecutionManager::controller_allowed_goal_duration_margin_
private

Definition at line 345 of file trajectory_execution_manager.h.

◆ controller_manager_

moveit_controller_manager::MoveItControllerManagerPtr trajectory_execution_manager::TrajectoryExecutionManager::controller_manager_
private

Definition at line 331 of file trajectory_execution_manager.h.

◆ controller_manager_loader_

std::unique_ptr<pluginlib::ClassLoader<moveit_controller_manager::MoveItControllerManager> > trajectory_execution_manager::TrajectoryExecutionManager::controller_manager_loader_
private

Definition at line 330 of file trajectory_execution_manager.h.

◆ csm_

planning_scene_monitor::CurrentStateMonitorPtr trajectory_execution_manager::TrajectoryExecutionManager::csm_
private

Definition at line 304 of file trajectory_execution_manager.h.

◆ current_context_

int trajectory_execution_manager::TrajectoryExecutionManager::current_context_
private

Definition at line 323 of file trajectory_execution_manager.h.

◆ event_topic_subscriber_

ros::Subscriber trajectory_execution_manager::TrajectoryExecutionManager::event_topic_subscriber_
private

Definition at line 307 of file trajectory_execution_manager.h.

◆ execution_complete_

bool trajectory_execution_manager::TrajectoryExecutionManager::execution_complete_
private

Definition at line 326 of file trajectory_execution_manager.h.

◆ execution_complete_condition_

boost::condition_variable trajectory_execution_manager::TrajectoryExecutionManager::execution_complete_condition_
private

Definition at line 319 of file trajectory_execution_manager.h.

◆ execution_duration_monitoring_

bool trajectory_execution_manager::TrajectoryExecutionManager::execution_duration_monitoring_
private

Definition at line 338 of file trajectory_execution_manager.h.

◆ EXECUTION_EVENT_TOPIC

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

Definition at line 94 of file trajectory_execution_manager.h.

◆ execution_state_mutex_

boost::mutex trajectory_execution_manager::TrajectoryExecutionManager::execution_state_mutex_
private

Definition at line 315 of file trajectory_execution_manager.h.

◆ execution_thread_

std::unique_ptr<boost::thread> trajectory_execution_manager::TrajectoryExecutionManager::execution_thread_
private

Definition at line 313 of file trajectory_execution_manager.h.

◆ execution_thread_mutex_

boost::mutex trajectory_execution_manager::TrajectoryExecutionManager::execution_thread_mutex_
private

Definition at line 316 of file trajectory_execution_manager.h.

◆ execution_velocity_scaling_

double trajectory_execution_manager::TrajectoryExecutionManager::execution_velocity_scaling_
private

Definition at line 350 of file trajectory_execution_manager.h.

◆ joints_allowed_start_tolerance_

std::map<std::string, double> trajectory_execution_manager::TrajectoryExecutionManager::joints_allowed_start_tolerance_
private

Definition at line 349 of file trajectory_execution_manager.h.

◆ known_controllers_

std::map<std::string, ControllerInformation> trajectory_execution_manager::TrajectoryExecutionManager::known_controllers_
private

Definition at line 309 of file trajectory_execution_manager.h.

◆ last_execution_status_

moveit_controller_manager::ExecutionStatus trajectory_execution_manager::TrajectoryExecutionManager::last_execution_status_
private

Definition at line 321 of file trajectory_execution_manager.h.

◆ manage_controllers_

bool trajectory_execution_manager::TrajectoryExecutionManager::manage_controllers_
private

Definition at line 310 of file trajectory_execution_manager.h.

◆ node_handle_

ros::NodeHandle trajectory_execution_manager::TrajectoryExecutionManager::node_handle_
private

Definition at line 305 of file trajectory_execution_manager.h.

◆ reconfigure_impl_

DynamicReconfigureImpl* trajectory_execution_manager::TrajectoryExecutionManager::reconfigure_impl_
private

Definition at line 335 of file trajectory_execution_manager.h.

◆ robot_model_

moveit::core::RobotModelConstPtr trajectory_execution_manager::TrajectoryExecutionManager::robot_model_
private

Definition at line 303 of file trajectory_execution_manager.h.

◆ root_node_handle_

ros::NodeHandle trajectory_execution_manager::TrajectoryExecutionManager::root_node_handle_
private

Definition at line 306 of file trajectory_execution_manager.h.

◆ time_index_

std::vector<ros::Time> trajectory_execution_manager::TrajectoryExecutionManager::time_index_
private

Definition at line 324 of file trajectory_execution_manager.h.

◆ time_index_mutex_

boost::mutex trajectory_execution_manager::TrajectoryExecutionManager::time_index_mutex_
mutableprivate

Definition at line 325 of file trajectory_execution_manager.h.

◆ trajectories_

std::vector<TrajectoryExecutionContext*> trajectory_execution_manager::TrajectoryExecutionManager::trajectories_
private

Definition at line 328 of file trajectory_execution_manager.h.

◆ verbose_

bool trajectory_execution_manager::TrajectoryExecutionManager::verbose_
private

Definition at line 333 of file trajectory_execution_manager.h.

◆ wait_for_trajectory_completion_

bool trajectory_execution_manager::TrajectoryExecutionManager::wait_for_trajectory_completion_
private

Definition at line 351 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 Sun Mar 3 2024 03:24:16