Program Listing for File gripper_action_controller.hpp

Return to documentation for file (include/gripper_controllers/gripper_action_controller.hpp)

// Copyright 2014, SRI International
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
//     http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.


#ifndef GRIPPER_CONTROLLERS__GRIPPER_ACTION_CONTROLLER_HPP_
#define GRIPPER_CONTROLLERS__GRIPPER_ACTION_CONTROLLER_HPP_

// C++ standard
#include <cassert>
#include <memory>
#include <stdexcept>
#include <string>

// ROS
#include "rclcpp/rclcpp.hpp"

// ROS messages
#include "control_msgs/action/gripper_command.hpp"

// rclcpp_action
#include "rclcpp_action/create_server.hpp"

// ros_controls
#include "controller_interface/controller_interface.hpp"
#include "gripper_controllers/visibility_control.hpp"
#include "hardware_interface/loaned_command_interface.hpp"
#include "hardware_interface/loaned_state_interface.hpp"
#include "realtime_tools/realtime_buffer.h"
#include "realtime_tools/realtime_server_goal_handle.h"

// Project
#include "gripper_controllers/hardware_interface_adapter.hpp"

// auto-generated by generate_parameter_library
#include "gripper_action_controller_parameters.hpp"

namespace gripper_action_controller
{
template <const char * HardwareInterface>
class GripperActionController : public controller_interface::ControllerInterface
{
public:
  struct Commands
  {
    double position_;    // Last commanded position
    double max_effort_;  // Max allowed effort
  };

  GRIPPER_ACTION_CONTROLLER_PUBLIC GripperActionController();

  GRIPPER_ACTION_CONTROLLER_PUBLIC
  controller_interface::InterfaceConfiguration command_interface_configuration() const override;

  GRIPPER_ACTION_CONTROLLER_PUBLIC
  controller_interface::InterfaceConfiguration state_interface_configuration() const override;

  GRIPPER_ACTION_CONTROLLER_PUBLIC
  controller_interface::return_type update(
    const rclcpp::Time & time, const rclcpp::Duration & period) override;

  GRIPPER_ACTION_CONTROLLER_PUBLIC
  controller_interface::CallbackReturn on_init() override;

  GRIPPER_ACTION_CONTROLLER_PUBLIC
  controller_interface::CallbackReturn on_configure(
    const rclcpp_lifecycle::State & previous_state) override;

  GRIPPER_ACTION_CONTROLLER_PUBLIC
  controller_interface::CallbackReturn on_activate(
    const rclcpp_lifecycle::State & previous_state) override;

  GRIPPER_ACTION_CONTROLLER_PUBLIC
  controller_interface::CallbackReturn on_deactivate(
    const rclcpp_lifecycle::State & previous_state) override;

  realtime_tools::RealtimeBuffer<Commands> command_;
  // pre-allocated memory that is re-used to set the realtime buffer
  Commands command_struct_, command_struct_rt_;

protected:
  using GripperCommandAction = control_msgs::action::GripperCommand;
  using ActionServer = rclcpp_action::Server<GripperCommandAction>;
  using ActionServerPtr = ActionServer::SharedPtr;
  using GoalHandle = rclcpp_action::ServerGoalHandle<GripperCommandAction>;
  using RealtimeGoalHandle =
    realtime_tools::RealtimeServerGoalHandle<control_msgs::action::GripperCommand>;
  using RealtimeGoalHandlePtr = std::shared_ptr<RealtimeGoalHandle>;
  using RealtimeGoalHandleBuffer = realtime_tools::RealtimeBuffer<RealtimeGoalHandlePtr>;

  using HwIfaceAdapter = HardwareInterfaceAdapter<HardwareInterface>;

  bool update_hold_position_;

  bool verbose_ = false;
  std::string name_;
  std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>
    joint_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_;

  HwIfaceAdapter hw_iface_adapter_;

  RealtimeGoalHandleBuffer
    rt_active_goal_;
  control_msgs::action::GripperCommand::Result::SharedPtr pre_alloc_result_;

  rclcpp::Duration action_monitor_period_;

  // ROS API
  ActionServerPtr action_server_;

  rclcpp::TimerBase::SharedPtr goal_handle_timer_;

  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();

  rclcpp::Time last_movement_time_ = rclcpp::Time(0, 0, RCL_ROS_TIME);
  double computed_command_;

  void check_for_success(
    const rclcpp::Time & time, double error_position, double current_position,
    double current_velocity);
};

}  // namespace gripper_action_controller

#include "gripper_controllers/gripper_action_controller_impl.hpp"

#endif  // GRIPPER_CONTROLLERS__GRIPPER_ACTION_CONTROLLER_HPP_