trajectory.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, 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 the Willow Garage 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 #ifndef TRAJECTORY_ROLLOUT_TRAJECTORY_H_
35 #define TRAJECTORY_ROLLOUT_TRAJECTORY_H_
36 
37 #include <vector>
38 
39 namespace base_local_planner {
44  class Trajectory {
45  public:
49  Trajectory();
50 
58  Trajectory(double xv, double yv, double thetav, double time_delta, unsigned int num_pts);
59 
60  double xv_, yv_, thetav_;
61 
62  double cost_;
63 
64  double time_delta_;
65 
73  void getPoint(unsigned int index, double& x, double& y, double& th) const;
74 
82  void setPoint(unsigned int index, double x, double y, double th);
83 
90  void addPoint(double x, double y, double th);
91 
98  void getEndpoint(double& x, double& y, double& th) const;
99 
103  void resetPoints();
104 
109  unsigned int getPointsSize() const;
110 
111  private:
112  std::vector<double> x_pts_;
113  std::vector<double> y_pts_;
114  std::vector<double> th_pts_;
115 
116  };
117 };
118 #endif
base_local_planner::Trajectory::resetPoints
void resetPoints()
Clear the trajectory's points.
Definition: trajectory.cpp:97
base_local_planner::Trajectory::xv_
double xv_
Definition: trajectory.h:92
base_local_planner::Trajectory::time_delta_
double time_delta_
The time gap between points.
Definition: trajectory.h:96
base_local_planner::Trajectory::addPoint
void addPoint(double x, double y, double th)
Add a point to the end of a trajectory.
Definition: trajectory.cpp:91
base_local_planner::Trajectory::setPoint
void setPoint(unsigned int index, double x, double y, double th)
Set a point within the trajectory.
Definition: trajectory.cpp:85
base_local_planner::Trajectory::cost_
double cost_
The cost/score of the trajectory.
Definition: trajectory.h:94
base_local_planner::Trajectory::x_pts_
std::vector< double > x_pts_
The x points in the trajectory.
Definition: trajectory.h:144
base_local_planner::Trajectory::yv_
double yv_
Definition: trajectory.h:92
base_local_planner::Trajectory::getEndpoint
void getEndpoint(double &x, double &y, double &th) const
Get the last point of the trajectory.
Definition: trajectory.cpp:103
base_local_planner::Trajectory::getPoint
void getPoint(unsigned int index, double &x, double &y, double &th) const
Get a point within the trajectory.
Definition: trajectory.cpp:79
base_local_planner::Trajectory::getPointsSize
unsigned int getPointsSize() const
Return the number of points in the trajectory.
Definition: trajectory.cpp:109
base_local_planner
Definition: costmap_model.h:44
base_local_planner::Trajectory::th_pts_
std::vector< double > th_pts_
The theta points in the trajectory.
Definition: trajectory.h:146
base_local_planner::Trajectory::thetav_
double thetav_
The x, y, and theta velocities of the trajectory.
Definition: trajectory.h:92
base_local_planner::Trajectory::Trajectory
Trajectory()
Default constructor.
Definition: trajectory.cpp:69
base_local_planner::Trajectory::y_pts_
std::vector< double > y_pts_
The y points in the trajectory.
Definition: trajectory.h:145


base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:24