moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
simple_sampler.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 trajectory operator that samples the next global trajectory waypoint as local goal constraint
37 based on the current robot state. When the waypoint is reached the index that marks the current local goal constraint
38 is updated to the next global trajectory waypoint. Global trajectory updates simply replace the reference trajectory.
39 */
40
43
45{
47{
48public:
49 SimpleSampler() = default;
50 ~SimpleSampler() override = default;
51
52 bool initialize([[maybe_unused]] const rclcpp::Node::SharedPtr& node,
53 const moveit::core::RobotModelConstPtr& robot_model, const std::string& group_name) override;
54 moveit_msgs::action::LocalPlanner::Feedback
55 addTrajectorySegment(const robot_trajectory::RobotTrajectory& new_trajectory) override;
56 moveit_msgs::action::LocalPlanner::Feedback
58 robot_trajectory::RobotTrajectory& local_trajectory) override;
59 double getTrajectoryProgress([[maybe_unused]] const moveit::core::RobotState& current_state) override;
60 bool reset() override;
61
62private:
63 std::size_t
64 next_waypoint_index_; // Indicates which reference trajectory waypoint is the current local goal constrained
65 moveit_msgs::action::LocalPlanner::Feedback feedback_; // Empty feedback
67 const moveit::core::JointModelGroup* joint_group_;
68};
69} // namespace moveit::hybrid_planning
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition robot_state.h:90
bool initialize(const rclcpp::Node::SharedPtr &node, const moveit::core::RobotModelConstPtr &robot_model, const std::string &group_name) override
moveit_msgs::action::LocalPlanner::Feedback addTrajectorySegment(const robot_trajectory::RobotTrajectory &new_trajectory) override
moveit_msgs::action::LocalPlanner::Feedback getLocalTrajectory(const moveit::core::RobotState &current_state, robot_trajectory::RobotTrajectory &local_trajectory) override
double getTrajectoryProgress(const moveit::core::RobotState &current_state) override
Maintain a sequence of waypoints and the time durations between these waypoints.