Go to the documentation of this file.
42 #include <moveit_msgs/RobotTrajectory.h>
43 #include <sensor_msgs/JointState.h>
44 #include <std_msgs/String.h>
47 #include <boost/thread.hpp>
73 struct TrajectoryExecutionContext
85 const planning_scene_monitor::CurrentStateMonitorPtr& csm);
89 const planning_scene_monitor::CurrentStateMonitorPtr& csm,
bool manage_controllers);
133 bool push(
const moveit_msgs::RobotTrajectory& trajectory,
const std::string& controller =
"");
137 bool push(
const trajectory_msgs::JointTrajectory& trajectory,
const std::string& controller =
"");
144 bool push(
const trajectory_msgs::JointTrajectory& trajectory,
const std::vector<std::string>& controllers);
151 bool push(
const moveit_msgs::RobotTrajectory& trajectory,
const std::vector<std::string>& controllers);
154 const std::vector<TrajectoryExecutionContext*>&
getTrajectories()
const;
162 bool auto_clear =
true);
233 bool validate(
const TrajectoryExecutionContext& context)
const;
234 bool configure(TrajectoryExecutionContext& context,
const moveit_msgs::RobotTrajectory& trajectory,
235 const std::vector<std::string>& controllers);
241 bool distributeTrajectory(
const moveit_msgs::RobotTrajectory& trajectory,
const std::vector<std::string>& controllers,
242 std::vector<moveit_msgs::RobotTrajectory>& parts);
244 bool findControllers(
const std::set<std::string>& actuated_joints, std::size_t controller_count,
245 const std::vector<std::string>& available_controllers,
246 std::vector<std::string>& selected_controllers);
249 const std::vector<std::string>& available_controllers,
250 std::vector<std::string>& selected_controllers,
252 const std::set<std::string>& actuated_joints);
254 const std::vector<std::string>& available_controllers,
255 std::vector<std::string>& selected_controllers);
264 void receiveEvent(
const std_msgs::StringConstPtr& event);
272 planning_scene_monitor::CurrentStateMonitorPtr
csm_;
290 std::vector<moveit_controller_manager::MoveItControllerHandlePtr>
active_handles_;
std::vector< ros::Time > time_index_
bool validate(const TrajectoryExecutionContext &context) const
Validate first point of trajectory matches current robot state.
boost::function< void(const moveit_controller_manager::ExecutionStatus &)> ExecutionCompleteCallback
double execution_velocity_scaling_
boost::condition_variable execution_complete_condition_
moveit_controller_manager::ExecutionStatus executeAndWait(bool auto_clear=true)
std::unique_ptr< pluginlib::ClassLoader< moveit_controller_manager::MoveItControllerManager > > controller_manager_loader_
void stopExecution(bool auto_clear=true)
Stop whatever executions are active, if any.
void setWaitForTrajectoryCompletion(bool flag)
Enable or disable waiting for trajectory completion.
bool ensureActiveController(const std::string &controller)
Make sure a particular controller is active.
bool selectControllers(const std::set< std::string > &actuated_joints, const std::vector< std::string > &available_controllers, std::vector< std::string > &selected_controllers)
void setExecutionVelocityScaling(double scaling)
planning_scene_monitor::CurrentStateMonitorPtr csm_
ros::NodeHandle node_handle_
bool ensureActiveControllersForJoints(const std::vector< std::string > &joints)
Make sure the active controllers are such that trajectories that actuate joints in the specified set ...
moveit_controller_manager::ExecutionStatus getLastExecutionStatus() const
Return the controller status for the last attempted execution.
bool isControllerActive(const std::string &controller)
Check if a controller is active.
moveit_controller_manager::ExecutionStatus last_execution_status_
bool ensureActiveControllers(const std::vector< std::string > &controllers)
Make sure a particular set of controllers are active.
bool checkControllerCombination(std::vector< std::string > &controllers, const std::set< std::string > &actuated_joints)
void setAllowedExecutionDurationScaling(double scaling)
std::map< std::string, double > controller_allowed_goal_duration_margin_
void receiveEvent(const std_msgs::StringConstPtr &event)
const std::vector< TrajectoryExecutionContext * > & getTrajectories() const
Get the trajectories to be executed.
moveit_controller_manager::MoveItControllerManagerPtr controller_manager_
bool execution_duration_monitoring_
void stopExecutionInternal()
std::vector< moveit_msgs::RobotTrajectory > trajectory_parts_
MOVEIT_CLASS_FORWARD(TrajectoryExecutionManager)
DynamicReconfigureImpl * reconfigure_impl_
ros::NodeHandle root_node_handle_
bool executePart(std::size_t part_index)
double allowed_start_tolerance_
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 execute(const ExecutionCompleteCallback &callback=ExecutionCompleteCallback(), bool auto_clear=true)
Start the execution of pushed trajectories; this does not wait for completion, but calls a callback w...
std::vector< TrajectoryExecutionContext * > trajectories_
bool areControllersActive(const std::vector< std::string > &controllers)
Check if a set of controllers are active.
std::vector< moveit_controller_manager::MoveItControllerHandlePtr > active_handles_
std::vector< std::string > controllers_
The controllers to use for executing the different trajectory parts;.
static const std::string EXECUTION_EVENT_TOPIC
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')
void setAllowedGoalDurationMargin(double margin)
void updateJointsAllowedStartTolerance()
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)
boost::mutex execution_thread_mutex_
void updateControllerState(const std::string &controller, const ros::Duration &age)
void reloadControllerInformation()
void updateControllersState(const ros::Duration &age)
std::pair< int, int > getCurrentExpectedTrajectoryIndex() const
std::vector< std::vector< std::string > > selected_options
moveit::core::RobotModelConstPtr robot_model_
void executeThread(const ExecutionCompleteCallback &callback, const PathSegmentCompleteCallback &part_callback, bool auto_clear)
moveit_controller_manager::ExecutionStatus waitForExecution()
~TrajectoryExecutionManager()
Destructor. Cancels all running trajectories (if any)
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.
bool configure(TrajectoryExecutionContext &context, const moveit_msgs::RobotTrajectory &trajectory, const std::vector< std::string > &controllers)
bool ensureActiveControllersForGroup(const std::string &group)
Make sure the active controllers are such that trajectories that actuate joints in the specified grou...
std::map< std::string, double > joints_allowed_start_tolerance_
bool wait_for_trajectory_completion_
double allowed_goal_duration_margin_
bool distributeTrajectory(const moveit_msgs::RobotTrajectory &trajectory, const std::vector< std::string > &controllers, std::vector< moveit_msgs::RobotTrajectory > &parts)
void clear()
Clear the trajectories to execute.
boost::mutex execution_state_mutex_
bool push(const moveit_msgs::RobotTrajectory &trajectory, const std::string &controller="")
std::unique_ptr< boost::thread > execution_thread_
boost::mutex time_index_mutex_
double getJointAllowedStartTolerance(std::string const &jointName) const
std::map< std::string, double > controller_allowed_execution_duration_scaling_
bool isManagingControllers() const
If this function returns true, then this instance of the manager is allowed to load/unload/switch con...
ros::Subscriber event_topic_subscriber_
double allowed_execution_duration_scaling_
void enableExecutionDurationMonitoring(bool flag)
bool waitForRobotToStop(const TrajectoryExecutionContext &context, double wait_time=1.0)
Data structure that represents information necessary to execute a trajectory.
boost::function< void(std::size_t)> PathSegmentCompleteCallback
std::map< std::string, ControllerInformation > known_controllers_
void setAllowedStartTolerance(double tolerance)
Set joint-value tolerance for validating trajectory's start point against current robot state.
void loadControllerParams()
planning
Author(s): Ioan Sucan
, Sachin Chitta
autogenerated on Thu Nov 21 2024 03:24:18