ros2_control - rolling
Loading...
Searching...
No Matches
Classes | Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | List of all members
parallel_gripper_action_controller::GripperActionController Class Reference

Controller for executing a ParallelGripperCommand action. More...

#include <parallel_gripper_action_controller.hpp>

Inheritance diagram for parallel_gripper_action_controller::GripperActionController:
Inheritance graph
[legend]
Collaboration diagram for parallel_gripper_action_controller::GripperActionController:
Collaboration graph
[legend]

Classes

struct  Commands
 Store position and max effort in struct to allow easier realtime buffer usage. More...
 

Public Member Functions

controller_interface::InterfaceConfiguration command_interface_configuration () const override
 command_interface_configuration This controller requires the position command interfaces for the controlled joints
 
controller_interface::InterfaceConfiguration state_interface_configuration () const override
 command_interface_configuration This controller requires the position and velocity state interfaces for the controlled joints
 
controller_interface::return_type update (const rclcpp::Time &time, const rclcpp::Duration &period) override
 Control step update. Command interfaces are updated based on on reference inputs and current states. The method called in the (real-time) control loop.
 
controller_interface::CallbackReturn on_init () override
 Extending interface with initialization method which is individual for each controller.
 
controller_interface::CallbackReturn on_configure (const rclcpp_lifecycle::State &previous_state) override
 
controller_interface::CallbackReturn on_activate (const rclcpp_lifecycle::State &previous_state) override
 
controller_interface::CallbackReturn on_deactivate (const rclcpp_lifecycle::State &previous_state) override
 
- Public Member Functions inherited from controller_interface::ControllerInterface
bool is_chainable () const final
 Controller is not chainable.
 
std::vector< hardware_interface::StateInterface::ConstSharedPtr > export_state_interfaces () final
 A non-chainable controller doesn't export any state interfaces.
 
std::vector< hardware_interface::CommandInterface::SharedPtr > export_reference_interfaces () final
 Controller has no reference interfaces.
 
bool set_chained_mode (bool chained_mode) final
 Controller is not chainable, therefore no chained mode can be set.
 
bool is_in_chained_mode () const final
 Controller can not be in chained mode.
 
- Public Member Functions inherited from controller_interface::ControllerInterfaceBase
virtual void assign_interfaces (std::vector< hardware_interface::LoanedCommandInterface > &&command_interfaces, std::vector< hardware_interface::LoanedStateInterface > &&state_interfaces)
 Method that assigns the Loaned interfaces to the controller.
 
virtual void release_interfaces ()
 Method that releases the Loaned interfaces from the controller.
 
return_type init (const std::string &controller_name, const std::string &urdf, unsigned int cm_update_rate, const std::string &node_namespace, const rclcpp::NodeOptions &node_options)
 
return_type init (const controller_interface::ControllerInterfaceParams &params)
 
const rclcpp_lifecycle::State & configure ()
 Custom configure method to read additional parameters for controller-nodes.
 
ControllerUpdateStatus trigger_update (const rclcpp::Time &time, const rclcpp::Duration &period)
 Trigger update method. This method is used by the controller_manager to trigger the update method of the controller. The method is used to trigger the update method of the controller synchronously or asynchronously, based on the controller configuration. The method called in the (real-time) control loop.
 
std::shared_ptr< rclcpp_lifecycle::LifecycleNode > get_node ()
 
std::shared_ptr< const rclcpp_lifecycle::LifecycleNode > get_node () const
 
const rclcpp_lifecycle::State & get_lifecycle_state () const
 Get the current lifecycle state of the controller node.
 
uint8_t get_lifecycle_id () const
 Get the lifecycle id of the controller node that is cached internally to avoid calls to get_lifecycle_state() in the real-time control loop.
 
unsigned int get_update_rate () const
 
bool is_async () const
 
const std::string & get_robot_description () const
 
const std::unordered_map< std::string, joint_limits::JointLimits > & get_hard_joint_limits () const
 Get the unordered map of joint limits that are defined in the robot description.
 
const std::unordered_map< std::string, joint_limits::SoftJointLimits > & get_soft_joint_limits () const
 Get the unordered map of soft joint limits that are defined in the robot description.
 
virtual rclcpp::NodeOptions define_custom_node_options () const
 Method used by the controller_manager for base NodeOptions to instantiate the Lifecycle node of the controller upon loading the controller.
 
template<typename ParameterT >
auto auto_declare (const std::string &name, const ParameterT &default_value)
 Declare and initialize a parameter with a type.
 
void wait_for_trigger_update_to_finish ()
 Method to wait for any running async update cycle to finish after finishing the current cycle. This is needed to be called before deactivating the controller by the controller_manager, so that the interfaces still exist when the controller finishes its cycle and then it's exits.
 
void prepare_for_deactivation ()
 Method to prepare the controller for deactivation. This method is called by the controller manager before deactivating the controller. The method is used to prepare the controller for deactivation, e.g., to stop triggering the update cycles further. This method is especially needed for controllers running in async mode and different frequency than the control manager.
 
std::string get_name () const
 
void enable_introspection (bool enable)
 Enable or disable introspection of the controller.
 

Protected Types

using GripperCommandAction = control_msgs::action::ParallelGripperCommand
 
using ActionServer = rclcpp_action::Server< GripperCommandAction >
 
using ActionServerPtr = ActionServer::SharedPtr
 
using GoalHandle = rclcpp_action::ServerGoalHandle< GripperCommandAction >
 
using RealtimeGoalHandle = realtime_tools::RealtimeServerGoalHandle< control_msgs::action::ParallelGripperCommand >
 
using RealtimeGoalHandlePtr = std::shared_ptr< RealtimeGoalHandle >
 
using RealtimeGoalHandleBox = realtime_tools::RealtimeThreadSafeBox< RealtimeGoalHandlePtr >
 

Protected Member Functions

rclcpp_action::GoalResponse goal_callback (const rclcpp_action::GoalUUID &uuid, std::shared_ptr< const GripperCommandAction::Goal > goal)
 
rclcpp_action::CancelResponse cancel_callback (const std::shared_ptr< GoalHandle > goal_handle)
 
void accepted_callback (std::shared_ptr< GoalHandle > goal_handle)
 
void preempt_active_goal ()
 
void set_hold_position ()
 
void check_for_success (const rclcpp::Time &time, double error_position, double current_position, double current_velocity)
 Check for success and publish appropriate result and feedback.
 

Protected Attributes

realtime_tools::RealtimeThreadSafeBox< Commandscommand_
 
Commands command_struct_
 
Commands command_struct_rt_
 
std::string name_
 Controller name.
 
std::optional< std::reference_wrapper< hardware_interface::LoanedCommandInterface > > joint_position_command_interface_
 
std::optional< std::reference_wrapper< hardware_interface::LoanedCommandInterface > > joint_effort_command_interface_
 
std::optional< std::reference_wrapper< hardware_interface::LoanedCommandInterface > > joint_speed_command_interface_
 
std::optional< std::reference_wrapper< hardware_interface::LoanedStateInterface > > joint_position_state_interface_
 
std::optional< std::reference_wrapper< hardware_interface::LoanedStateInterface > > joint_velocity_state_interface_
 
std::shared_ptr< ParamListener > param_listener_
 
Params params_
 
RealtimeGoalHandleBox rt_active_goal_
 Container for the currently active action goal, if any.
 
control_msgs::action::ParallelGripperCommand::Result::SharedPtr pre_alloc_result_
 
rclcpp::Duration action_monitor_period_
 
ActionServerPtr action_server_
 
rclcpp::TimerBase::SharedPtr goal_handle_timer_
 
realtime_tools::RealtimeThreadSafeBox< rclcpp::Time > last_movement_time_
 Store stall time.
 
double computed_command_
 Computed command.
 
- Protected Attributes inherited from controller_interface::ControllerInterfaceBase
std::vector< hardware_interface::LoanedCommandInterfacecommand_interfaces_
 Loaned command interfaces.
 
std::vector< hardware_interface::LoanedStateInterfacestate_interfaces_
 Loaned state interfaces.
 
pal_statistics::RegistrationsRAII stats_registrations_
 

Detailed Description

Controller for executing a ParallelGripperCommand action.

Template Parameters
HardwareInterfaceController hardware interface. Currently hardware_interface::HW_IF_POSITION and hardware_interface::HW_IF_EFFORT are supported out-of-the-box.

Member Function Documentation

◆ command_interface_configuration()

controller_interface::InterfaceConfiguration parallel_gripper_action_controller::GripperActionController::command_interface_configuration ( ) const
overridevirtual

command_interface_configuration This controller requires the position command interfaces for the controlled joints

Implements controller_interface::ControllerInterfaceBase.

◆ on_init()

controller_interface::CallbackReturn parallel_gripper_action_controller::GripperActionController::on_init ( )
overridevirtual

Extending interface with initialization method which is individual for each controller.

Implements controller_interface::ControllerInterfaceBase.

◆ state_interface_configuration()

controller_interface::InterfaceConfiguration parallel_gripper_action_controller::GripperActionController::state_interface_configuration ( ) const
overridevirtual

command_interface_configuration This controller requires the position and velocity state interfaces for the controlled joints

Implements controller_interface::ControllerInterfaceBase.

◆ update()

controller_interface::return_type parallel_gripper_action_controller::GripperActionController::update ( const rclcpp::Time &  time,
const rclcpp::Duration &  period 
)
overridevirtual

Control step update. Command interfaces are updated based on on reference inputs and current states. The method called in the (real-time) control loop.

Parameters
[in]timeThe time at the start of this control loop iteration
[in]periodThe measured time since the last control loop iteration
Returns
return_type::OK if update is successfully, otherwise return_type::ERROR.

Implements controller_interface::ControllerInterfaceBase.


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