moveit2
The MoveIt Motion Planning Framework for ROS 2.
trajectory_operator_interface.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2020, 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 PickNik Inc. 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: Sebastian Jahr
36  Description: Defines an interface for a trajectory operator plugin implementation for the local planner component node.
37  */
38 
39 #pragma once
40 
41 #include <rclcpp/rclcpp.hpp>
42 #include <rclcpp_action/rclcpp_action.hpp>
43 
44 #include <moveit_msgs/msg/robot_trajectory.hpp>
45 #include <moveit_msgs/msg/constraints.hpp>
46 
47 #include <moveit_msgs/action/local_planner.hpp>
48 
51 
53 {
61 {
62 public:
68  virtual ~TrajectoryOperatorInterface() = default;
76  virtual bool initialize(const rclcpp::Node::SharedPtr& node, const moveit::core::RobotModelConstPtr& robot_model,
77  const std::string& group_name) = 0;
78 
84  virtual moveit_msgs::action::LocalPlanner::Feedback
86 
92  virtual moveit_msgs::action::LocalPlanner::Feedback
94  robot_trajectory::RobotTrajectory& local_trajectory) = 0;
95 
102  virtual double getTrajectoryProgress(const moveit::core::RobotState& current_state) = 0;
103 
108  virtual bool reset() = 0;
109 
110 protected:
111  // Reference trajectory to be precessed
112  robot_trajectory::RobotTrajectoryPtr reference_trajectory_;
113  std::string group_;
114 };
115 } // namespace moveit::hybrid_planning
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
virtual bool initialize(const rclcpp::Node::SharedPtr &node, const moveit::core::RobotModelConstPtr &robot_model, const std::string &group_name)=0
virtual moveit_msgs::action::LocalPlanner::Feedback addTrajectorySegment(const robot_trajectory::RobotTrajectory &new_trajectory)=0
TrajectoryOperatorInterface & operator=(TrajectoryOperatorInterface &&)=default
TrajectoryOperatorInterface(const TrajectoryOperatorInterface &)=default
virtual moveit_msgs::action::LocalPlanner::Feedback getLocalTrajectory(const moveit::core::RobotState &current_state, robot_trajectory::RobotTrajectory &local_trajectory)=0
virtual double getTrajectoryProgress(const moveit::core::RobotState &current_state)=0
TrajectoryOperatorInterface & operator=(const TrajectoryOperatorInterface &)=default
TrajectoryOperatorInterface(TrajectoryOperatorInterface &&)=default
Maintain a sequence of waypoints and the time durations between these waypoints.