MoveIt Pro API
Core Behaviors for MoveIt Pro
Loading...
Searching...
No Matches
moveit_pro::behaviors::SetRos2Parameter Class Referencefinal

Set any ROS2 parameter on any node at runtime via the standard set_parameters service. More...

#include <set_ros2_parameter.hpp>

Inheritance diagram for moveit_pro::behaviors::SetRos2Parameter:
Collaboration diagram for moveit_pro::behaviors::SetRos2Parameter:

Public Member Functions

 SetRos2Parameter (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources)
 
 SetRos2Parameter (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources, std::unique_ptr< ClientInterfaceBase< SetParameters > > client_interface)
 
- Public Member Functions inherited from moveit_pro::behaviors::ServiceClientBehaviorBase< SetParameters >
 ServiceClientBehaviorBase (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources)
 Constructs ServiceClientBehaviorBase using the RclcppClientInterface.
 
 ServiceClientBehaviorBase (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources, std::unique_ptr< ClientInterfaceBase< SetParameters > > client_interface)
 Constructs ServiceClientBehaviorBase using a user-provided implementation of ClientInterfaceBase.
 
 ~ServiceClientBehaviorBase () override=default
 
- Public Member Functions inherited from moveit_pro::behaviors::AsyncBehaviorBase
 AsyncBehaviorBase (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources)
 
 ~AsyncBehaviorBase () override=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_pro::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 ()
 

Additional Inherited Members

- Static Public Attributes inherited from moveit_pro::behaviors::ServiceClientBehaviorBase< SetParameters >
static constexpr std::chrono::seconds kTimeoutWaitForServiceServer
 
- Protected Member Functions inherited from moveit_pro::behaviors::ServiceClientBehaviorBase< SetParameters >
virtual tl::expected< bool, std::string > processResponse (const typename ServiceT::Response &)
 Optional user-provided function to process the service response after the service has finished.
 
tl::expected< void, std::string > doHalt () override
 Handles halting logic which is specific to the service client behavior implementation.
 
- Protected Member Functions inherited from moveit_pro::behaviors::AsyncBehaviorBase
void notifyCanHalt ()
 Called when runAsync() finishes to notify onHalted() that the async process has finished.
 
- Protected Attributes inherited from moveit_pro::behaviors::SharedResourcesNode< BT::StatefulActionNode >
std::shared_ptr< BehaviorContextshared_resources_
 

Detailed Description

Set any ROS2 parameter on any node at runtime via the standard set_parameters service.

This Behavior calls the node_name/set_parameters service to update a single parameter. It accepts the parameter value as a string and parses it according to the specified type. Useful for tuning Nav2 costmap parameters (e.g. robot_radius, footprint), controller gains, or any other parameter exposed via the standard ROS2 parameter service.

For array types, provide comma-separated values (e.g. "0.1,0.2,0.3" for double_array).

Data Port Name Port Type Object Type
node_name input std::string
parameter_name input std::string
parameter_value input std::string
parameter_type input std::string
response_timeout input double
wait_for_server_available_timeout input double

Constructor & Destructor Documentation

◆ SetRos2Parameter() [1/2]

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

◆ SetRos2Parameter() [2/2]

moveit_pro::behaviors::SetRos2Parameter::SetRos2Parameter ( const std::string &  name,
const BT::NodeConfiguration &  config,
const std::shared_ptr< BehaviorContext > &  shared_resources,
std::unique_ptr< ClientInterfaceBase< SetParameters > >  client_interface 
)
explicit

Member Function Documentation

◆ metadata()

BT::KeyValueVector moveit_pro::behaviors::SetRos2Parameter::metadata ( )
static

◆ providedPorts()

BT::PortsList moveit_pro::behaviors::SetRos2Parameter::providedPorts ( )
static

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