MoveIt Pro API
Core Behaviors for MoveIt Pro
Loading...
Searching...
No Matches
moveit_studio::behaviors::BaseTrajectoryExecutor< ActionType > Class Template Referenceabstract

Base class for trajectory execution implementations. More...

#include <execute_mtc_solution.hpp>

Inheritance diagram for moveit_studio::behaviors::BaseTrajectoryExecutor< ActionType >:
Collaboration diagram for moveit_studio::behaviors::BaseTrajectoryExecutor< ActionType >:

Public Types

using ClientGoalHandle = rclcpp_action::ClientGoalHandle< ActionType >
 
using ActionClient = rclcpp_action::Client< ActionType >
 

Public Member Functions

 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
 
virtual tl::expected< bool, std::string > initialize (const std::string &action_name)=0
 Initialize the trajectory execution pipeline.
 
virtual 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)=0
 Execute a trajectory with the given parameters.
 
virtual tl::expected< void, std::string > cancelExecution ()=0
 Cancel the currently active trajectory execution.
 

Public Attributes

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

static constexpr std::chrono::seconds kWaitForServerTimeout { 2 }
 
static constexpr std::chrono::seconds kGoalRequestTimeout { 2 }
 
static constexpr std::chrono::seconds kCancelRequestTimeout { 5 }
 

Detailed Description

template<typename ActionType>
class moveit_studio::behaviors::BaseTrajectoryExecutor< ActionType >

Base class for trajectory execution implementations.

Factors out common functionality shared between different trajectory executor types, e.g. initialize the action client, sending a goal, waiting for a result, etc. Templated on the action type, e.g. FollowJointTrajectory (JTC) vs. FollowJointTrajectoryWithAdmittance (JTAC).

Member Typedef Documentation

◆ ActionClient

template<typename ActionType >
using moveit_studio::behaviors::BaseTrajectoryExecutor< ActionType >::ActionClient = rclcpp_action::Client<ActionType>

◆ ClientGoalHandle

template<typename ActionType >
using moveit_studio::behaviors::BaseTrajectoryExecutor< ActionType >::ClientGoalHandle = rclcpp_action::ClientGoalHandle<ActionType>

Constructor & Destructor Documentation

◆ BaseTrajectoryExecutor()

template<typename ActionType >
moveit_studio::behaviors::BaseTrajectoryExecutor< ActionType >::BaseTrajectoryExecutor ( rclcpp::Node::SharedPtr  node,
rclcpp::CallbackGroup::SharedPtr  callback_group 
)
inlineexplicit

Member Function Documentation

◆ cancelActiveGoal()

template<typename ActionType >
tl::expected< void, std::string > moveit_studio::behaviors::BaseTrajectoryExecutor< ActionType >::cancelActiveGoal ( )

◆ extractErrorMessage()

template<typename ActionType >
virtual std::string moveit_studio::behaviors::BaseTrajectoryExecutor< ActionType >::extractErrorMessage ( const typename ActionType::Result::SharedPtr &  result) const
pure virtual

Derived classes implement this to extract error messages from the action result.

◆ initializeActionClient()

template<typename ActionType >
tl::expected< bool, std::string > moveit_studio::behaviors::BaseTrajectoryExecutor< ActionType >::initializeActionClient ( const std::string &  action_name,
const std::string &  server_description 
)

Common action client initialization logic.

◆ sendGoal()

template<typename ActionType >
tl::expected< typename BaseTrajectoryExecutor< ActionType >::ClientGoalHandle::SharedPtr, std::string > moveit_studio::behaviors::BaseTrajectoryExecutor< ActionType >::sendGoal ( const typename ActionType::Goal &  goal,
std::size_t  trajectory_index 
)

Common goal sending logic.

◆ waitForResult()

template<typename ActionType >
tl::expected< bool, std::string > moveit_studio::behaviors::BaseTrajectoryExecutor< ActionType >::waitForResult ( typename ClientGoalHandle::SharedPtr  goal_handle,
double  goal_duration_tolerance_seconds,
std::size_t  trajectory_index 
)

Common result waiting logic.

Member Data Documentation

◆ action_client_

template<typename ActionType >
ActionClient::SharedPtr moveit_studio::behaviors::BaseTrajectoryExecutor< ActionType >::action_client_

◆ active_goal_handle_

template<typename ActionType >
ClientGoalHandle::SharedPtr moveit_studio::behaviors::BaseTrajectoryExecutor< ActionType >::active_goal_handle_

◆ callback_group_

template<typename ActionType >
rclcpp::CallbackGroup::SharedPtr moveit_studio::behaviors::BaseTrajectoryExecutor< ActionType >::callback_group_

◆ current_action_name_

template<typename ActionType >
std::string moveit_studio::behaviors::BaseTrajectoryExecutor< ActionType >::current_action_name_

◆ goal_mutex_

template<typename ActionType >
std::mutex moveit_studio::behaviors::BaseTrajectoryExecutor< ActionType >::goal_mutex_

◆ kCancelRequestTimeout

template<typename ActionType >
constexpr std::chrono::seconds moveit_studio::behaviors::BaseTrajectoryExecutor< ActionType >::kCancelRequestTimeout { 5 }
staticconstexpr

◆ kGoalRequestTimeout

template<typename ActionType >
constexpr std::chrono::seconds moveit_studio::behaviors::BaseTrajectoryExecutor< ActionType >::kGoalRequestTimeout { 2 }
staticconstexpr

◆ kWaitForServerTimeout

template<typename ActionType >
constexpr std::chrono::seconds moveit_studio::behaviors::BaseTrajectoryExecutor< ActionType >::kWaitForServerTimeout { 2 }
staticconstexpr

◆ node_

template<typename ActionType >
rclcpp::Node::SharedPtr moveit_studio::behaviors::BaseTrajectoryExecutor< ActionType >::node_

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