|
MoveIt Pro API
Core Behaviors for MoveIt Pro
|
Standard trajectory execution (e.g. JTC) pipeline implementation. More...
#include <execute_mtc_solution.hpp>


Public Types | |
| using | ActionType = control_msgs::action::FollowJointTrajectory |
Public Types inherited from moveit_studio::behaviors::BaseTrajectoryExecutor< control_msgs::action::FollowJointTrajectory > | |
| using | ClientGoalHandle = rclcpp_action::ClientGoalHandle< control_msgs::action::FollowJointTrajectory > |
| using | ActionClient = rclcpp_action::Client< control_msgs::action::FollowJointTrajectory > |
Public Member Functions | |
| StandardTrajectoryExecutor (rclcpp::Node::SharedPtr node, rclcpp::CallbackGroup::SharedPtr callback_group) | |
| Constructor for StandardTrajectoryExecutor. | |
| tl::expected< bool, std::string > | initialize (const std::string &action_name) override |
| Initialize the trajectory execution pipeline. | |
| tl::expected< bool, std::string > | executeTrajectory (const trajectory_msgs::msg::JointTrajectory &joint_trajectory, const std::optional< moveit_pro_controllers_msgs::msg::AdmittanceParameters > &admittance_params, const std::optional< double > &goal_tolerance, const std::optional< double > &path_tolerance, const std::optional< std::vector< double > > &absolute_force_torque_threshold, double goal_duration_tolerance_seconds, std::size_t index) override |
| Execute a trajectory with the given parameters. | |
| tl::expected< void, std::string > | cancelExecution () override |
| Cancel the currently active trajectory execution. | |
Public Member Functions inherited from moveit_studio::behaviors::BaseTrajectoryExecutor< control_msgs::action::FollowJointTrajectory > | |
| BaseTrajectoryExecutor (rclcpp::Node::SharedPtr node, rclcpp::CallbackGroup::SharedPtr callback_group) | |
| tl::expected< bool, std::string > | initializeActionClient (const std::string &action_name, const std::string &server_description) |
| Common action client initialization logic. | |
| tl::expected< typename ClientGoalHandle::SharedPtr, std::string > | sendGoal (const typename ActionType::Goal &goal, std::size_t trajectory_index) |
| Common goal sending logic. | |
| tl::expected< bool, std::string > | waitForResult (typename ClientGoalHandle::SharedPtr goal_handle, double goal_duration_tolerance_seconds, std::size_t trajectory_index) |
| Common result waiting logic. | |
| tl::expected< void, std::string > | cancelActiveGoal () |
| virtual std::string | extractErrorMessage (const typename ActionType::Result::SharedPtr &result) const=0 |
| Derived classes implement this to extract error messages from the action result. | |
Public Member Functions inherited from moveit_studio::behaviors::TrajectoryExecutionPipeline | |
| virtual | ~TrajectoryExecutionPipeline ()=default |
Protected Member Functions | |
| std::string | extractErrorMessage (const ActionType::Result::SharedPtr &result) const override |
Additional Inherited Members | |
Public Attributes inherited from moveit_studio::behaviors::BaseTrajectoryExecutor< control_msgs::action::FollowJointTrajectory > | |
| rclcpp::Node::SharedPtr | node_ |
| rclcpp::CallbackGroup::SharedPtr | callback_group_ |
| ActionClient::SharedPtr | action_client_ |
| ClientGoalHandle::SharedPtr | active_goal_handle_ |
| std::string | current_action_name_ |
| std::mutex | goal_mutex_ |
Static Public Attributes inherited from moveit_studio::behaviors::BaseTrajectoryExecutor< control_msgs::action::FollowJointTrajectory > | |
| static constexpr std::chrono::seconds | kWaitForServerTimeout |
| static constexpr std::chrono::seconds | kGoalRequestTimeout |
| static constexpr std::chrono::seconds | kCancelRequestTimeout |
Standard trajectory execution (e.g. JTC) pipeline implementation.
| using moveit_studio::behaviors::StandardTrajectoryExecutor::ActionType = control_msgs::action::FollowJointTrajectory |
|
explicit |
Constructor for StandardTrajectoryExecutor.
| node | ROS node for creating action client |
| callback_group | Callback group for action client operations |
|
overridevirtual |
Cancel the currently active trajectory execution.
Implements moveit_studio::behaviors::TrajectoryExecutionPipeline.
|
overridevirtual |
Execute a trajectory with the given parameters.
| joint_trajectory | The joint trajectory to execute. |
| admittance_params | Admittance control parameters (may be ignored by non-JTAC implementations). |
| goal_tolerance | Optional goal position tolerance. |
| path_tolerance | Optional path position tolerance. |
| absolute_force_torque_threshold | Optional force/torque limits (JTAC-specific). |
| goal_duration_tolerance_seconds | Timeout in seconds (negative means wait indefinitely). |
| index | Sub-trajectory index for error reporting. |
Implements moveit_studio::behaviors::TrajectoryExecutionPipeline.
|
overrideprotected |
|
overridevirtual |
Initialize the trajectory execution pipeline.
| action_name | Name of the trajectory action server |
Implements moveit_studio::behaviors::TrajectoryExecutionPipeline.