MoveIt Pro Behavior
Core Behaviors for MoveIt Pro
|
A base class for behaviors which need to asynchronously run a function that might take a long time to complete. More...
#include <async_behavior_base.hpp>
Inherits moveit_studio::behaviors::SharedResourcesNode< BT::StatefulActionNode >.
Inherited by moveit_studio::behaviors::ActionClientBehaviorBase< GripperCommand >, moveit_studio::behaviors::ActionClientBehaviorBase< moveit_pro_controllers_msgs::action::FollowJointTrajectoryWithAdmittance >, moveit_studio::behaviors::ActionClientBehaviorBase< ExecuteTaskSolution >, moveit_studio::behaviors::ActionClientBehaviorBase< FollowJointTrajectory >, moveit_studio::behaviors::ActionClientBehaviorBase< NavigateToPose >, moveit_studio::behaviors::ActionClientBehaviorBase< NavigateThroughPoses >, moveit_studio::behaviors::ActionClientBehaviorBase< DoTeleoperate >, moveit_studio::behaviors::ActionClientBehaviorBase< GetMasks2D >, moveit_studio::behaviors::ActionClientBehaviorBase< CalibratePose >, moveit_studio::behaviors::ActionClientBehaviorBase< ShapeCompletion >, moveit_studio::behaviors::GetMessageFromTopicBehaviorBase< sensor_msgs::msg::CameraInfo >, moveit_studio::behaviors::GetMessageFromTopicBehaviorBase< sensor_msgs::msg::Image >, moveit_studio::behaviors::GetMessageFromTopicBehaviorBase< sensor_msgs::msg::PointCloud2 >, moveit_studio::behaviors::ServiceClientBehaviorBase< RetrievePose >, moveit_studio::behaviors::ServiceClientBehaviorBase< RetrieveJointState >, moveit_studio::behaviors::ServiceClientBehaviorBase< SendPointCloud2 >, moveit_studio::behaviors::ServiceClientBehaviorBase< SwitchPrimaryView >, moveit_studio::behaviors::ServiceClientBehaviorBase< moveit_studio_agent_msgs::srv::DetachOrRemoveTool >, moveit_studio::behaviors::ServiceClientBehaviorBase< RequestTextFromUser >, moveit_studio::behaviors::ServiceClientBehaviorBase< RequestPointsFromUser >, moveit_studio::behaviors::ServiceClientBehaviorBase< std_srvs::srv::Empty >, moveit_studio::behaviors::ServiceClientBehaviorBase< GetPlanningScene >, moveit_studio::behaviors::ServiceClientBehaviorBase< moveit_studio_agent_msgs::srv::AddTool >, moveit_studio::behaviors::ServiceClientBehaviorBase< moveit_studio_agent_msgs::srv::AttachTool >, moveit_studio::behaviors::ServiceClientBehaviorBase< SetStringArray >, moveit_studio::behaviors::ServiceClientBehaviorBase< Trigger >, moveit_studio::behaviors::ServiceClientBehaviorBase< RetrieveBehaviorParameter >, moveit_studio::behaviors::ServiceClientBehaviorBase< AdjustPose >, moveit_studio::behaviors::ServiceClientBehaviorBase< ApplyPlanningScene >, moveit_studio::behaviors::TeleoperateBase< control_msgs::msg::JointJog >, moveit_studio::behaviors::TeleoperateBase< geometry_msgs::msg::TwistStamped >, moveit_studio::behaviors::ActionClientBehaviorBase< ActionT >, moveit_studio::behaviors::CheckCuboidSimilarity, moveit_studio::behaviors::CropPointsInBox, moveit_studio::behaviors::CropPointsInSphere, moveit_studio::behaviors::DetectAprilTags, moveit_studio::behaviors::FindMaskedObjects, moveit_studio::behaviors::FitLineSegmentToMask3D, moveit_studio::behaviors::GetGraspableObjectsFromMasks3D, moveit_studio::behaviors::GetMasks3DFromMasks2D, moveit_studio::behaviors::GetMeshNormalPoses, moveit_studio::behaviors::GetMessageFromTopicBehaviorBase< MessageT >, moveit_studio::behaviors::GetPointCloudFromMask3D, moveit_studio::behaviors::GetPoseFromPixelCoords, moveit_studio::behaviors::LoadPointCloudFromFile, moveit_studio::behaviors::MergePointClouds, moveit_studio::behaviors::PlanMTCTask, moveit_studio::behaviors::RegisterPointClouds, moveit_studio::behaviors::SaveImageToFile, moveit_studio::behaviors::SavePointCloudToFile, moveit_studio::behaviors::SendPointCloudToUI, moveit_studio::behaviors::ServiceClientBehaviorBase< ServiceT >, moveit_studio::behaviors::TeleoperateBase< CommandT >, moveit_studio::behaviors::TransformPointCloud, moveit_studio::behaviors::TransformPointCloudFrame, and moveit_studio::behaviors::ValidateTrajectory.
Public Member Functions | |
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(). More... | |
BT::NodeStatus | onRunning () override |
Required implementation of BT::StatefulActionNode::onRunning(). More... | |
void | onHalted () override |
Required implementation of BT::StatefulActionNode::onHalted(). More... | |
void | resetStatus () |
Resets the internal status of this node. More... | |
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. More... | |
Protected Member Functions | |
virtual tl::expected< bool, std::string > | doWork ()=0 |
User-implemented function which handles executing the potentially-long-running process. More... | |
virtual tl::expected< void, std::string > | doHalt () |
Optionally implement additional work needed to cleanly interrupt the async process. More... | |
virtual std::shared_future< tl::expected< bool, std::string > > & | getFuture ()=0 |
Gets the shared future which is used to monitor the progress of the async process. More... | |
void | notifyCanHalt () |
Called when runAsync() finishes to notify onHalted() that the async process has finished. More... | |
Additional Inherited Members | |
Protected Attributes inherited from moveit_studio::behaviors::SharedResourcesNode< BT::StatefulActionNode > | |
std::shared_ptr< BehaviorContext > | shared_resources_ |
A base class for behaviors which need to asynchronously run a function that might take a long time to complete.
moveit_studio::behaviors::AsyncBehaviorBase::AsyncBehaviorBase | ( | const std::string & | name, |
const BT::NodeConfiguration & | config, | ||
const std::shared_ptr< BehaviorContext > & | shared_resources | ||
) |
|
virtualdefault |
|
inlineprotectedvirtual |
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 in moveit_studio::behaviors::TeleoperateBase< CommandT >, moveit_studio::behaviors::TeleoperateBase< control_msgs::msg::JointJog >, and moveit_studio::behaviors::TeleoperateBase< geometry_msgs::msg::TwistStamped >.
|
protectedpure virtual |
User-implemented function which handles executing the potentially-long-running process.
This function is called within an async process in a separate thread.
Implemented in moveit_studio::behaviors::TransformPointCloudFrame, moveit_studio::behaviors::TransformPointCloud, moveit_studio::behaviors::RegisterPointClouds, moveit_studio::behaviors::MergePointClouds, moveit_studio::behaviors::GetPoseFromPixelCoords, moveit_studio::behaviors::GetPointCloudFromMask3D, moveit_studio::behaviors::GetMasks3DFromMasks2D, moveit_studio::behaviors::GetGraspableObjectsFromMasks3D, moveit_studio::behaviors::FitLineSegmentToMask3D, moveit_studio::behaviors::FindMaskedObjects, moveit_studio::behaviors::TeleoperateBase< CommandT >, moveit_studio::behaviors::TeleoperateBase< control_msgs::msg::JointJog >, moveit_studio::behaviors::TeleoperateBase< geometry_msgs::msg::TwistStamped >, and moveit_studio::behaviors::GetMeshNormalPoses.
|
protectedpure virtual |
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.
|
protected |
Called when runAsync() finishes to notify onHalted() that the async process has finished.
Behaviors inheriting from AsyncBehaviorBase may also call this function in doWork() to notify onHalted() that doHalt() can be called immediately.
An example of a case where this is needed is when implementing a ROS action client behavior, because in that case onHalted() must block until the action goal response is received and a goal handle is available so that the goal handle can be used to cancel the goal.
|
override |
Required implementation of BT::StatefulActionNode::onHalted().
If an action goal is in-progress, this cancels it and blocks until execute_action_future_ has been set, which indicates that the async process has finished.
|
override |
Required implementation of BT::StatefulActionNode::onRunning().
Checks the status of execute_action_future_. If the future has been set, analyze its contents to determine if the behavior has succeeded or failed.
|
override |
Required implementation of BT::StatefulActionNode::onStart().
This runs doWork() within an async process associated with execute_action_future_.
|
inline |
Resets the internal status of this node.
Sets the status to IDLE, so that the behavior can be executed again after is has already finished.