Controller for executing a ParallelGripperCommand
action.
More...
#include <parallel_gripper_action_controller.hpp>
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 |
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 |
![]() | |
bool | is_chainable () const final |
std::vector< hardware_interface::StateInterface::ConstSharedPtr > | export_state_interfaces () final |
std::vector< hardware_interface::CommandInterface::SharedPtr > | export_reference_interfaces () final |
bool | set_chained_mode (bool chained_mode) final |
bool | is_in_chained_mode () const final |
![]() | |
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) |
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) |
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 |
unsigned int | get_update_rate () const |
bool | is_async () const |
const std::string & | get_robot_description () const |
virtual rclcpp::NodeOptions | define_custom_node_options () const |
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 () |
std::string | get_name () const |
void | enable_introspection (bool enable) |
Enable or disable introspection of the controller. | |
Public Attributes | |
realtime_tools::RealtimeBuffer< Commands > | command_ |
Commands | command_struct_ |
Commands | command_struct_rt_ |
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 | RealtimeGoalHandleBuffer = realtime_tools::RealtimeBuffer< RealtimeGoalHandlePtr > |
Protected Attributes | |
bool | update_hold_position_ |
bool | verbose_ = false |
Hard coded verbose flag to help in debugging. | |
std::string | name_ |
Controller name. | |
std::optional< std::reference_wrapper< hardware_interface::LoanedCommandInterface > > | joint_command_interface_ |
std::optional< std::reference_wrapper< hardware_interface::LoanedCommandInterface > > | effort_interface_ |
std::optional< std::reference_wrapper< hardware_interface::LoanedCommandInterface > > | speed_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_ |
RealtimeGoalHandleBuffer | 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_ |
rclcpp::Time | last_movement_time_ = rclcpp::Time(0, 0, RCL_ROS_TIME) |
Store stall time. | |
double | computed_command_ |
Computed command. | |
![]() | |
std::vector< hardware_interface::LoanedCommandInterface > | command_interfaces_ |
std::vector< hardware_interface::LoanedStateInterface > | state_interfaces_ |
pal_statistics::RegistrationsRAII | stats_registrations_ |
Controller for executing a ParallelGripperCommand
action.
HardwareInterface | Controller hardware interface. Currently hardware_interface::HW_IF_POSITION and hardware_interface::HW_IF_EFFORT are supported out-of-the-box. |
|
overridevirtual |
command_interface_configuration This controller requires the position command interfaces for the controlled joints
Implements controller_interface::ControllerInterfaceBase.
|
overridevirtual |
Extending interface with initialization method which is individual for each controller.
Implements controller_interface::ControllerInterfaceBase.
|
overridevirtual |
command_interface_configuration This controller requires the position and velocity state interfaces for the controlled joints
Implements controller_interface::ControllerInterfaceBase.
|
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.
[in] | time | The time at the start of this control loop iteration |
[in] | period | The measured time since the last control loop iteration |
Implements controller_interface::ControllerInterfaceBase.