Program Listing for File point_head.h

Return to documentation for file (/tmp/ws/src/robot_controllers/robot_controllers/include/robot_controllers/point_head.h)

/*********************************************************************
 *  Software License Agreement (BSD License)
 *
 *  Copyright (c) 2020, Michael Ferguson
 *  Copyright (c) 2014, Fetch Robotics Inc.
 *  Copyright (c) 2013, Unbounded Robotics Inc.
 *  All rights reserved.
 *
 *  Redistribution and use in source and binary forms, with or without
 *  modification, are permitted provided that the following conditions
 *  are met:
 *
 *   * Redistributions of source code must retain the above copyright
 *     notice, this list of conditions and the following disclaimer.
 *   * Redistributions in binary form must reproduce the above
 *     copyright notice, this list of conditions and the following
 *     disclaimer in the documentation and/or other materials provided
 *     with the distribution.
 *   * Neither the name of Unbounded Robotics nor the names of its
 *     contributors may be used to endorse or promote products derived
 *     from this software without specific prior written permission.
 *
 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
 *  POSSIBILITY OF SUCH DAMAGE.
 *********************************************************************/

// Author: Michael Ferguson

#ifndef ROBOT_CONTROLLERS__POINT_HEAD_H_
#define ROBOT_CONTROLLERS__POINT_HEAD_H_

#include <memory>
#include <mutex>
#include <string>
#include <vector>

#include "rclcpp/rclcpp.hpp"
#include "rclcpp_action/rclcpp_action.hpp"
#include "robot_controllers_interface/controller.h"
#include "robot_controllers_interface/joint_handle.h"
#include "robot_controllers_interface/controller_manager.h"
#include "tf2_ros/buffer.h"
#include "control_msgs/action/point_head.hpp"

#include "robot_controllers/trajectory.h"
#include "robot_controllers/trajectory_spline_sampler.h"

#include "kdl/tree.hpp"

namespace robot_controllers
{

class PointHeadController : public robot_controllers_interface::Controller
{
  using PointHeadAction = control_msgs::action::PointHead;
  using PointHeadGoal = rclcpp_action::ServerGoalHandle<PointHeadAction>;

public:
  PointHeadController() {}
  virtual ~PointHeadController() {}

  virtual int init(const std::string& name,
                   rclcpp::Node::SharedPtr node,
                   robot_controllers_interface::ControllerManagerPtr manager);

  virtual bool start();

  virtual bool stop(bool force);

  virtual bool reset();

  virtual void update(const rclcpp::Time& now, const rclcpp::Duration& dt);

  virtual std::string getType()
  {
    return "robot_controllers/PointHeadController";
  }

  virtual std::vector<std::string> getCommandedNames();

  virtual std::vector<std::string> getClaimedNames();

private:
  // rclcpp callbacks
  rclcpp_action::GoalResponse handle_goal(
    const rclcpp_action::GoalUUID & uuid,
    std::shared_ptr<const PointHeadAction::Goal> goal_handle);
  rclcpp_action::CancelResponse handle_cancel(
    const std::shared_ptr<PointHeadGoal> goal_handle);
  void handle_accepted(const std::shared_ptr<PointHeadGoal> goal_handle);

  // Execute the goal
  void execute(const std::shared_ptr<PointHeadGoal> goal_handle);

  // Handles to node, manager
  rclcpp::Node::SharedPtr node_;
  robot_controllers_interface::ControllerManagerPtr manager_;

  // Parameters
  std::string pan_parent_link_;
  std::string tilt_parent_link_;
  bool stop_with_action_;

  // Joint handles
  robot_controllers_interface::JointHandlePtr head_pan_;
  robot_controllers_interface::JointHandlePtr head_tilt_;

  // Trajectory generation
  std::shared_ptr<TrajectorySampler> sampler_;

  /*
   * In certain cases, we want to start a trajectory at our last sample,
   * for instance if we were pre-empted (as is often the case with teleop)
   * we need to use the velocity and position of the last sample as a
   * starting point.
   */
  TrajectoryPoint last_sample_;

  // RCLCPP action server
  rclcpp_action::Server<PointHeadAction>::SharedPtr server_;
  std::shared_ptr<PointHeadGoal> active_goal_;
  // This guards both the active_goal_ and the sampler_
  // Is recursive so we can call stop whenever we want
  std::recursive_mutex active_goal_mutex_;

  KDL::Tree kdl_tree_;
  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
};

}  // namespace robot_controllers

#endif  // ROBOT_CONTROLLERS__POINT_HEAD_H_