Class RpVacuumGripperController
Defined in File rp_vacuum_gripper_controller.hpp
Inheritance Relationships
Base Type
public controller_interface::ControllerInterface
Class Documentation
-
class RpVacuumGripperController : public controller_interface::ControllerInterface
Public Functions
-
RP_CONTROLLER_PUBLIC RpVacuumGripperController() = default
Construct a new ‘RpVacuumGripperController’ object.
- RP_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_init () override
Initialize the controller.
- RP_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_configure (const rclcpp_lifecycle::State &previous_state) override
Configure the controller.
- Parameters:
previous_state – Previous state of the controller.
- RP_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_activate (const rclcpp_lifecycle::State &previous_state) override
Activate the controller.
- Parameters:
previous_state – Previous state of the controller.
- RP_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_deactivate (const rclcpp_lifecycle::State &previous_state) override
Deactivate the controller.
- Parameters:
previous_state – Previous state of the controller.
- RP_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration command_interface_configuration () const override
Construct ‘InterfaceConfiguration’ object for the command interfaces.
- RP_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration state_interface_configuration () const override
Construct ‘InterfaceConfiguration’ object for the state interfaces.
- RP_CONTROLLER_PUBLIC controller_interface::return_type update (const rclcpp::Time &time, const rclcpp::Duration &period) override
Controller loop update.
- Parameters:
time – Current time.
period – Time elapsed since the last update.
Protected Functions
-
inline auto FindInterface(auto &interfaces, const auto &name)
-
void SetCommand(const std::string &name, const bool value)
-
bool GetState(const std::string &name)
-
rclcpp_action::GoalResponse HandleGoal(const rclcpp_action::GoalUUID &uuid, GripperCommandActionGoalPtr goal)
-
rclcpp_action::CancelResponse HandleCancel(const GripperCommandActionServerGoalHandlePtr goal_handle)
-
void HandleAccepted(const GripperCommandActionServerGoalHandlePtr goal_handle)
-
void Execute(const GripperCommandActionServerGoalHandlePtr goal_handle)
-
void PublishFeedback(const GripperCommandActionServerGoalHandlePtr goal_handle)
Protected Attributes
-
std::mutex current_goal_execution_mtx_
-
GripperCommandActionServerGoalHandlePtr current_goal_handle_
-
GripperCommandActionServerPtr gripper_command_action_server_
Action server for the gripper command.
-
std::shared_ptr<rp_vacuum_gripper_controller::ParamListener> param_listener_
Parameters listener pointer.
-
rp_vacuum_gripper_controller::Params params_
Parameters for the controller.
-
RP_CONTROLLER_PUBLIC RpVacuumGripperController() = default