Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
trajectory_generator.hpp
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, Locus Robotics
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 the copyright holder 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 HOLDER 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 #ifndef DWB_CORE__TRAJECTORY_GENERATOR_HPP_
36 #define DWB_CORE__TRAJECTORY_GENERATOR_HPP_
37 
38 #include <vector>
39 #include <string>
40 #include <memory>
41 #include "rclcpp/rclcpp.hpp"
42 #include "nav_2d_msgs/msg/twist2_d.hpp"
43 #include "dwb_msgs/msg/trajectory2_d.hpp"
44 #include "nav2_util/lifecycle_node.hpp"
45 
46 namespace dwb_core
47 {
48 
65 {
66 public:
67  typedef std::shared_ptr<dwb_core::TrajectoryGenerator> Ptr;
68 
69  virtual ~TrajectoryGenerator() {}
70 
75  virtual void initialize(
76  const nav2_util::LifecycleNode::SharedPtr & nh,
77  const std::string & plugin_name) = 0;
78  virtual void reset() {}
83  virtual void startNewIteration(const nav_2d_msgs::msg::Twist2D & current_velocity) = 0;
84 
89  virtual bool hasMoreTwists() = 0;
90 
95  virtual nav_2d_msgs::msg::Twist2D nextTwist() = 0;
96 
105  virtual std::vector<nav_2d_msgs::msg::Twist2D> getTwists(
106  const nav_2d_msgs::msg::Twist2D & current_velocity)
107  {
108  std::vector<nav_2d_msgs::msg::Twist2D> twists;
109  startNewIteration(current_velocity);
110  while (hasMoreTwists()) {
111  twists.push_back(nextTwist());
112  }
113  return twists;
114  }
115 
122  virtual dwb_msgs::msg::Trajectory2D generateTrajectory(
123  const geometry_msgs::msg::Pose2D & start_pose,
124  const nav_2d_msgs::msg::Twist2D & start_vel,
125  const nav_2d_msgs::msg::Twist2D & cmd_vel) = 0;
126 
134  virtual void setSpeedLimit(const double & speed_limit, const bool & percentage) = 0;
135 };
136 
137 } // namespace dwb_core
138 
139 #endif // DWB_CORE__TRAJECTORY_GENERATOR_HPP_
Interface for iterating through possible velocities and creating trajectories.
virtual nav_2d_msgs::msg::Twist2D nextTwist()=0
Return the next twist and advance the iteration.
virtual std::vector< nav_2d_msgs::msg::Twist2D > getTwists(const nav_2d_msgs::msg::Twist2D &current_velocity)
Get all the twists for an iteration.
virtual bool hasMoreTwists()=0
Test to see whether there are more twists to test.
virtual dwb_msgs::msg::Trajectory2D generateTrajectory(const geometry_msgs::msg::Pose2D &start_pose, const nav_2d_msgs::msg::Twist2D &start_vel, const nav_2d_msgs::msg::Twist2D &cmd_vel)=0
Given a cmd_vel in the robot's frame and initial conditions, generate a Trajectory2D.
virtual void initialize(const nav2_util::LifecycleNode::SharedPtr &nh, const std::string &plugin_name)=0
Initialize parameters as needed.
virtual void startNewIteration(const nav_2d_msgs::msg::Twist2D &current_velocity)=0
Start a new iteration based on the current velocity.
virtual void setSpeedLimit(const double &speed_limit, const bool &percentage)=0
Limits the maximum linear speed of the robot.