moveit2
The MoveIt Motion Planning Framework for ROS 2.
forward_trajectory.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: Simple local solver plugin that forwards the next waypoint of the sampled local trajectory.
37  The local solver stops for two conditions: invalid waypoint (likely due to collision) or if it has been stuck for
38  several iterations.
39  */
40 
41 #pragma once
42 
43 #include <rclcpp/rclcpp.hpp>
45 
47 {
49 {
50 public:
51  ForwardTrajectory() = default;
52  ~ForwardTrajectory() override = default;
53  bool initialize(const rclcpp::Node::SharedPtr& node,
54  const planning_scene_monitor::PlanningSceneMonitorPtr& planning_scene_monitor,
55  const std::string& /* unused */) override;
56  bool reset() override;
57 
58  moveit_msgs::action::LocalPlanner::Feedback
59  solve(const robot_trajectory::RobotTrajectory& local_trajectory,
60  const std::shared_ptr<const moveit_msgs::action::LocalPlanner::Goal> /* unused */,
61  trajectory_msgs::msg::JointTrajectory& local_solution) override;
62 
63 private:
64  rclcpp::Node::SharedPtr node_;
65  planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_;
66  bool path_invalidation_event_send_; // Send path invalidation event only once
67  bool stop_before_collision_;
68 
69  // Detect when the local planner gets stuck
70  size_t num_iterations_stuck_;
71  moveit::core::RobotStatePtr prev_waypoint_target_;
72 };
73 } // namespace moveit::hybrid_planning
moveit_msgs::action::LocalPlanner::Feedback solve(const robot_trajectory::RobotTrajectory &local_trajectory, const std::shared_ptr< const moveit_msgs::action::LocalPlanner::Goal >, trajectory_msgs::msg::JointTrajectory &local_solution) override
bool initialize(const rclcpp::Node::SharedPtr &node, const planning_scene_monitor::PlanningSceneMonitorPtr &planning_scene_monitor, const std::string &) override
Maintain a sequence of waypoints and the time durations between these waypoints.