moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
local_constraint_solver_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 local constraint solver 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
46
47#include <moveit_msgs/msg/robot_trajectory.hpp>
48#include <moveit_msgs/msg/constraints.hpp>
49
50#include <moveit_msgs/action/local_planner.hpp>
51
52#include <trajectory_msgs/msg/joint_trajectory.hpp>
53
55{
60{
61public:
72 virtual bool initialize(const rclcpp::Node::SharedPtr& node,
73 const planning_scene_monitor::PlanningSceneMonitorPtr& planning_scene_monitor,
74 const std::string& group_name) = 0;
75
83 virtual moveit_msgs::action::LocalPlanner::Feedback
85 const std::shared_ptr<const moveit_msgs::action::LocalPlanner::Goal> local_goal,
86 trajectory_msgs::msg::JointTrajectory& local_solution) = 0;
87
92 virtual bool reset() = 0;
93};
94} // namespace moveit::hybrid_planning
LocalConstraintSolverInterface(LocalConstraintSolverInterface &&)=default
virtual bool initialize(const rclcpp::Node::SharedPtr &node, const planning_scene_monitor::PlanningSceneMonitorPtr &planning_scene_monitor, const std::string &group_name)=0
LocalConstraintSolverInterface(const LocalConstraintSolverInterface &)=default
virtual moveit_msgs::action::LocalPlanner::Feedback solve(const robot_trajectory::RobotTrajectory &local_trajectory, const std::shared_ptr< const moveit_msgs::action::LocalPlanner::Goal > local_goal, trajectory_msgs::msg::JointTrajectory &local_solution)=0
LocalConstraintSolverInterface & operator=(const LocalConstraintSolverInterface &)=default
LocalConstraintSolverInterface & operator=(LocalConstraintSolverInterface &&)=default
Maintain a sequence of waypoints and the time durations between these waypoints.