MoveIt Pro Behavior
Core Behaviors for MoveIt Pro
moveit_studio::behaviors::SetAdmittanceParameters Class Referencefinal

Sets admittance parameters to be used in the 'ExecuteTrajectoryWithAdmittance' Behavior. More...

#include <set_admittance_parameters.hpp>

Inheritance diagram for moveit_studio::behaviors::SetAdmittanceParameters:
Collaboration diagram for moveit_studio::behaviors::SetAdmittanceParameters:

Public Member Functions

 SetAdmittanceParameters (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources)
 
BT::NodeStatus onStart () override
 
BT::NodeStatus onRunning () override
 
void onHalted () override
 
tl::expected< void, std::string > validateControllerType (const std::string &controller_name, const std::vector< std::string > &valid_controller_types)
 Validates the type of the controller as either an admittance controller or test controller. More...
 
tl::expected< void, std::string > updateOrCreateAdmittanceParameters (const AdmittanceControllerParams &params)
 Updates parameters for an existing ros2_control admittance controller, or creates an AdmittanceParameters message for a JTAC controller. 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...
 

Static Public Member Functions

static BT::PortsList providedPorts ()
 
static BT::KeyValueVector metadata ()
 

Additional Inherited Members

- Protected Attributes inherited from moveit_studio::behaviors::SharedResourcesNode< BT::StatefulActionNode >
std::shared_ptr< BehaviorContextshared_resources_
 

Detailed Description

Sets admittance parameters to be used in the 'ExecuteTrajectoryWithAdmittance' Behavior.

This behavior can be used to set admittance parameters for a JTAC controller. A set of parameters will be loaded from a YAML file and displayed in the UI for the user to modify. Any modifications will be stored back to the YAML file. If the given YAML file doesn't exist, a default set of parameters will be created. The parameters will also be returned in an output port as an 'AdmittanceParameters' message, which can be used as input to the 'ExecuteTrajectoryWithAdmittance' Behavior (JTAC controller).

Alternatively, this behavior can also be used to set admittance parameters for a ros2_control admittance controller. In this case, the parameters will be set via the parameter server and no output message will be created. This mode of operation is deprecated and only kept for compatibility with older setups that use the ros2_control admittance controller.

Data Port Name Port Type Object Type
config_file_name input std::string
admittance_parameters_msg output moveit_pro_controllers_msgs::msg::AdmittanceParameters

Constructor & Destructor Documentation

◆ SetAdmittanceParameters()

moveit_studio::behaviors::SetAdmittanceParameters::SetAdmittanceParameters ( const std::string &  name,
const BT::NodeConfiguration &  config,
const std::shared_ptr< BehaviorContext > &  shared_resources 
)
explicit

Member Function Documentation

◆ metadata()

BT::KeyValueVector moveit_studio::behaviors::SetAdmittanceParameters::metadata ( )
static

◆ onHalted()

void moveit_studio::behaviors::SetAdmittanceParameters::onHalted ( )
override

◆ onRunning()

BT::NodeStatus moveit_studio::behaviors::SetAdmittanceParameters::onRunning ( )
override

◆ onStart()

BT::NodeStatus moveit_studio::behaviors::SetAdmittanceParameters::onStart ( )
override

◆ providedPorts()

BT::PortsList moveit_studio::behaviors::SetAdmittanceParameters::providedPorts ( )
static

◆ updateOrCreateAdmittanceParameters()

tl::expected< void, std::string > moveit_studio::behaviors::SetAdmittanceParameters::updateOrCreateAdmittanceParameters ( const AdmittanceControllerParams params)

Updates parameters for an existing ros2_control admittance controller, or creates an AdmittanceParameters message for a JTAC controller.

Parameters
paramsStruct containing admittance parameters to set.
Returns
Nothing if successful, else an error.

◆ validateControllerType()

tl::expected< void, std::string > moveit_studio::behaviors::SetAdmittanceParameters::validateControllerType ( const std::string &  controller_name,
const std::vector< std::string > &  valid_controller_types 
)

Validates the type of the controller as either an admittance controller or test controller.

Parameters
controller_nameName of the controller to validate.
valid_controller_typesVector containing the valid controller types.
Returns
Nothing if successful, else an error.

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