Program Listing for File chainable_controller_interface.hpp

Return to documentation for file (include/controller_interface/chainable_controller_interface.hpp)

// Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt)
//
// 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 CONTROLLER_INTERFACE__CHAINABLE_CONTROLLER_INTERFACE_HPP_
#define CONTROLLER_INTERFACE__CHAINABLE_CONTROLLER_INTERFACE_HPP_

#include <memory>
#include <string>
#include <unordered_map>
#include <vector>

#include "controller_interface/controller_interface_base.hpp"
#include "hardware_interface/handle.hpp"

namespace controller_interface
{

class ChainableControllerInterface : public ControllerInterfaceBase
{
public:
  ChainableControllerInterface();

  virtual ~ChainableControllerInterface() = default;

  return_type update(const rclcpp::Time & time, const rclcpp::Duration & period) final;

  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;

protected:

  virtual std::vector<hardware_interface::StateInterface> on_export_state_interfaces();


  virtual std::vector<hardware_interface::CommandInterface> on_export_reference_interfaces();


  virtual bool on_set_chained_mode(bool chained_mode);


  virtual return_type update_reference_from_subscribers(
    const rclcpp::Time & time, const rclcpp::Duration & period) = 0;


  virtual return_type update_and_write_commands(
    const rclcpp::Time & time, const rclcpp::Duration & period) = 0;

  std::vector<std::string> exported_state_interface_names_;
  std::vector<hardware_interface::StateInterface::SharedPtr> ordered_exported_state_interfaces_;
  std::unordered_map<std::string, hardware_interface::StateInterface::SharedPtr>
    exported_state_interfaces_;
  // BEGIN (Handle export change): for backward compatibility
  std::vector<double> state_interfaces_values_;
  // END

  std::vector<std::string> exported_reference_interface_names_;
  // BEGIN (Handle export change): for backward compatibility
  std::vector<double> reference_interfaces_;
  // END
  std::vector<hardware_interface::CommandInterface::SharedPtr>
    ordered_exported_reference_interfaces_;
  std::unordered_map<std::string, hardware_interface::CommandInterface::SharedPtr>
    exported_reference_interfaces_;

private:
  bool in_chained_mode_ = false;
};

}  // namespace controller_interface

#endif  // CONTROLLER_INTERFACE__CHAINABLE_CONTROLLER_INTERFACE_HPP_