moveit2
The MoveIt Motion Planning Framework for ROS 2.
empty_controller_handle.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2022, PickNik Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Fraunhofer IPA nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Paul Gesel */
36 
37 #pragma once
38 
40 #include <rclcpp/rclcpp.hpp>
41 
43 {
44 /*
45  * An interface for controllers that have no handle, e.g. chained controllers like an Admittance controller
46  */
48 {
49 public:
50  /* Topics will map to name/ns/goal, name/ns/result, etc */
51  EmptyControllerHandle(const std::string& name, const std::string& logger_name)
52  : moveit_controller_manager::MoveItControllerHandle(name), logger_(rclcpp::get_logger(logger_name))
53  {
54  }
55 
56  bool sendTrajectory(const moveit_msgs::msg::RobotTrajectory& trajectory) override
57  {
58  RCLCPP_ERROR_STREAM(logger_, "This controller handle does not support trajectory execution.");
59  return false;
60  }
61 
62  bool cancelExecution() override
63  {
64  return true;
65  }
66 
71  bool waitForExecution(const rclcpp::Duration& /* timeout */) override
72  {
73  return true;
74  }
75 
81  {
83  }
84 
85 private:
86  const rclcpp::Logger logger_;
87 };
88 
89 } // end namespace moveit_simple_controller_manager
MoveIt sends commands to a controller via a handle that satisfies this interface.
MoveItControllerHandle(const std::string &name)
Each controller has a name. The handle is initialized with that name.
moveit_controller_manager::ExecutionStatus getLastExecutionStatus() override
Gets the last trajectory execution status.
bool waitForExecution(const rclcpp::Duration &) override
Function called when the TrajectoryExecutionManager waits for a trajectory to finish.
bool sendTrajectory(const moveit_msgs::msg::RobotTrajectory &trajectory) override
Send a trajectory to the controller.
bool cancelExecution() override
Cancel the execution of any motion using this controller.
EmptyControllerHandle(const std::string &name, const std::string &logger_name)
Namespace for the base class of a MoveIt controller manager.
name
Definition: setup.py:7