|
MoveIt Pro API
Core Behaviors for MoveIt Pro
|
Accepts a JointTrajectory message via an input data port, and executes it by sending a goal to either a standard FollowJointTrajectory action server (JTC) or a Joint Trajectory Admittance Controller (JTAC) action server, depending on the value of the execution_pipeline input port. More...
#include <execute_trajectory.hpp>


Public Member Functions | |
| ExecuteTrajectory (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) | |
| std::shared_future< tl::expected< bool, std::string > > & | getFuture () override |
| Gets the shared future which is used to monitor the progress of the async process. | |
Public Member Functions inherited from moveit_studio::behaviors::AsyncBehaviorBase | |
| AsyncBehaviorBase (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) | |
| virtual | ~AsyncBehaviorBase ()=default |
| BT::NodeStatus | onStart () override |
| Required implementation of BT::StatefulActionNode::onStart(). | |
| BT::NodeStatus | onRunning () override |
| Required implementation of BT::StatefulActionNode::onRunning(). | |
| void | onHalted () override |
| Required implementation of BT::StatefulActionNode::onHalted(). | |
| void | resetStatus () |
| Resets the internal status of this node. | |
Public Member Functions inherited from moveit_studio::behaviors::SharedResourcesNode< BT::StatefulActionNode > | |
| SharedResourcesNode (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) | |
| Constructor for SharedResourcesNode. Called by BT::BehaviorTreeFactory when creating a new behavior tree containing this node. | |
Static Public Member Functions | |
| static BT::PortsList | providedPorts () |
| static BT::KeyValueVector | metadata () |
Protected Member Functions | |
| tl::expected< bool, std::string > | doWork () override |
| User-implemented function which handles executing the potentially-long-running process. | |
| tl::expected< void, std::string > | doHalt () override |
| Optionally implement additional work needed to cleanly interrupt the async process. | |
Protected Member Functions inherited from moveit_studio::behaviors::AsyncBehaviorBase | |
| void | notifyCanHalt () |
| Called when runAsync() finishes to notify onHalted() that the async process has finished. | |
Additional Inherited Members | |
Protected Attributes inherited from moveit_studio::behaviors::SharedResourcesNode< BT::StatefulActionNode > | |
| std::shared_ptr< BehaviorContext > | shared_resources_ |
Accepts a JointTrajectory message via an input data port, and executes it by sending a goal to either a standard FollowJointTrajectory action server (JTC) or a Joint Trajectory Admittance Controller (JTAC) action server, depending on the value of the execution_pipeline input port.
This Behavior consolidates ExecuteFollowJointTrajectory and ExecuteTrajectoryWithAdmittance into a single Behavior.
| Data Port Name | Port Type | Object Type |
|---|---|---|
| execution_pipeline | Input | std::string |
| controller_action_name | Input | std::string |
| joint_trajectory_msg | Input | trajectory_msgs::msg::JointTrajectory |
| goal_position_tolerance | Input | double |
| path_position_tolerance | Input | double |
| absolute_force_torque_threshold | Input | std::vector<double> |
| admittance_parameters_msg | Input | moveit_pro_controllers_msgs::msg::AdmittanceParameters |
| goal_duration_tolerance | Input | double |
| moveit_studio::behaviors::ExecuteTrajectory::ExecuteTrajectory | ( | const std::string & | name, |
| const BT::NodeConfiguration & | config, | ||
| const std::shared_ptr< BehaviorContext > & | shared_resources | ||
| ) |
|
overrideprotectedvirtual |
Optionally implement additional work needed to cleanly interrupt the async process.
The default implementation of this function is a no-op which will not interrupt the async process. This will mean that onHalted will wait until the process finishes before returning.
Reimplemented from moveit_studio::behaviors::AsyncBehaviorBase.
|
overrideprotectedvirtual |
User-implemented function which handles executing the potentially-long-running process.
This function is called within an async process in a separate thread.
Implements moveit_studio::behaviors::AsyncBehaviorBase.
|
overridevirtual |
Gets the shared future which is used to monitor the progress of the async process.
Classes derived from AsyncBehaviorBase must implement getFuture() so that it returns a shared_future class member.
This exists to prevent destruction of the derived class while the async process is still in-progress. If the derived class is destroyed, the definitions of the functions used within doWork() will be destroyed too, which will result in the virtual functions in the base class being called instead and cause a fault.
This function will force derived classes to add an instance of this type and return a reference to it. The base class can then use this virtual function to access the shared future in functions like onStart.
By adding this virtual function we're properly demonstrating how this future depends on things from the derived class and the natural flow of object lifetimes will do the hard work for us. The std::shared_future destructor will get the value of the future before the derived class is destructed assuming it's the last reference to the shared state. Doing it this way means neither the base nor derived class should need to implement a destructor which is a nice property to have.
Implements moveit_studio::behaviors::AsyncBehaviorBase.
|
static |
|
static |