All non-template implementation for the templated MPCBehaviorBase class.
More...
#include <mpc_behavior_base.hpp>
|
| MPCBehaviorBase (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< moveit_studio::behaviors::BehaviorContext > &shared_resources, const std::function< tl::expected< void, std::string >(const BT::TreeNode &)> &set_residual_ports) |
|
| ~MPCBehaviorBase () override |
|
tl::expected< void, std::string > | doHalt () override |
| Optionally implement additional work needed to cleanly interrupt the async process.
|
|
BT::NodeStatus | onStart () override |
|
tl::expected< bool, std::string > | doWork () override |
| User-implemented function which handles executing the potentially-long-running process.
|
|
virtual bool | finished () |
| Determines whether the behavior has finished execution.
|
|
std::shared_future< tl::expected< bool, std::string > > & | getFuture () override |
| Classes derived from AsyncBehaviorBase must implement getFuture() so that it returns a shared_future class member.
|
|
| 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.
|
|
| 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.
|
|
|
std::shared_future< tl::expected< bool, std::string > > | future_ |
| Classes derived from AsyncBehaviorBase must have this shared_future as a class member.
|
|
trajectory_msgs::msg::JointTrajectory | trajectory_msg |
| Trajectory message to be populated by MPC.
|
|
rclcpp_action::Client< control_msgs::action::FollowJointTrajectory >::SharedPtr | client |
| Action client to send trajectories to a joint trajectory controller.
|
|
std::shared_ptr< planning_scene_monitor::PlanningSceneMonitor > | planning_scene_monitor |
| Shared pointer to the planning scene monitor used for monitoring and updating the planning scene.
|
|
moveit::core::RobotModelConstPtr | robot_model |
| Constant pointer to the robot model used for planning and execution.
|
|
std::string | planning_group |
| The name of the planning group used for motion planning.
|
|
std::function< tl::expected< void, std::string >(const BT::TreeNode &)> | set_residual_ports |
| Callback to set the residual parameters from the BT ports.
|
|
All non-template implementation for the templated MPCBehaviorBase class.
◆ MPCBehaviorBase()
◆ ~MPCBehaviorBase()
moveit_studio::behaviors::internal::MPCBehaviorBase::~MPCBehaviorBase |
( |
| ) |
|
|
overridedefault |
◆ doHalt()
tl::expected< void, std::string > moveit_studio::behaviors::internal::MPCBehaviorBase::doHalt |
( |
| ) |
|
|
overridevirtual |
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.
- Returns
- Return an empty tl::expected<void, std::string> if the additional work to halt was successful. Return an error message if something failed while doing additional work to halt.
Reimplemented from moveit_studio::behaviors::AsyncBehaviorBase.
◆ doWork()
tl::expected< bool, std::string > moveit_studio::behaviors::internal::MPCBehaviorBase::doWork |
( |
| ) |
|
|
overridevirtual |
User-implemented function which handles executing the potentially-long-running process.
This function is called within an async process in a separate thread.
- Returns
- A tl::expected which contains a bool indicating task success if the process completed successfully or was canceled, or an error message if the process failed unexpectedly.
Implements moveit_studio::behaviors::AsyncBehaviorBase.
◆ finished()
virtual bool moveit_studio::behaviors::internal::MPCBehaviorBase::finished |
( |
| ) |
|
|
inlinevirtual |
Determines whether the behavior has finished execution.
This method can be overridden by derived classes to customize the termination condition for the behavior. By default, it always returns false.
- Returns
- true if the behavior has finished, false otherwise.
◆ getFuture()
std::shared_future< tl::expected< bool, std::string > > & moveit_studio::behaviors::internal::MPCBehaviorBase::getFuture |
( |
| ) |
|
|
overridevirtual |
◆ onStart()
BT::NodeStatus moveit_studio::behaviors::internal::MPCBehaviorBase::onStart |
( |
| ) |
|
|
override |
◆ providedProblemParametersPorts()
BT::PortsList moveit_studio::behaviors::internal::MPCBehaviorBase::providedProblemParametersPorts |
( |
| ) |
|
|
static |
Provides the list of BT ports required for problem parameters.
- Returns
- A list of BT ports for problem parameters.
◆ providedSolverParametersPorts()
BT::PortsList moveit_studio::behaviors::internal::MPCBehaviorBase::providedSolverParametersPorts |
( |
| ) |
|
|
static |
Provides the list of BT ports required for solver parameters.
- Returns
- A list of BT ports for solver parameters.
◆ client
rclcpp_action::Client<control_msgs::action::FollowJointTrajectory>::SharedPtr moveit_studio::behaviors::internal::MPCBehaviorBase::client |
Action client to send trajectories to a joint trajectory controller.
◆ future_
std::shared_future<tl::expected<bool, std::string> > moveit_studio::behaviors::internal::MPCBehaviorBase::future_ |
Classes derived from AsyncBehaviorBase must have this shared_future as a class member.
◆ planning_group
std::string moveit_studio::behaviors::internal::MPCBehaviorBase::planning_group |
The name of the planning group used for motion planning.
◆ planning_scene_monitor
std::shared_ptr<planning_scene_monitor::PlanningSceneMonitor> moveit_studio::behaviors::internal::MPCBehaviorBase::planning_scene_monitor |
Shared pointer to the planning scene monitor used for monitoring and updating the planning scene.
◆ robot_model
moveit::core::RobotModelConstPtr moveit_studio::behaviors::internal::MPCBehaviorBase::robot_model |
Constant pointer to the robot model used for planning and execution.
◆ set_residual_ports
std::function<tl::expected<void, std::string>(const BT::TreeNode&)> moveit_studio::behaviors::internal::MPCBehaviorBase::set_residual_ports |
Callback to set the residual parameters from the BT ports.
◆ trajectory_msg
trajectory_msgs::msg::JointTrajectory moveit_studio::behaviors::internal::MPCBehaviorBase::trajectory_msg |
Trajectory message to be populated by MPC.
The documentation for this class was generated from the following files: