traj_gen.h
Go to the documentation of this file.
1 /*******************************************************************************
2  * BSD 3-Clause License
3  *
4  * Copyright (c) 2021, Qiayuan Liao
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 are met:
9  *
10  * * Redistributions of source code must retain the above copyright notice, this
11  * list of conditions and the following disclaimer.
12  *
13  * * Redistributions in binary form must reproduce the above copyright notice,
14  * this list of conditions and the following disclaimer in the documentation
15  * and/or other materials provided with the distribution.
16  *
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived from
19  * this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24  * ARE
25  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
26  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
27  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
28  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
30  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
31  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
32  *******************************************************************************/
33 
34 //
35 // Created by qiayuan on 3/21/20.
36 //
37 
38 #pragma once
39 
40 #include <cmath>
41 #include <string>
42 #include "math_utilities.h"
43 
44 template <typename T>
45 class RampTraj
46 {
47 private:
48  T start_{}; // Start pos and velocity
49  T target_{}; // End pos and velocity
50  T time_total_{};
51  T time_acc_{};
52  T time_start_{};
53 
54  T acc_{};
55  T speed_{}; // When in uniform speed
56  T a0_, b0_, c0_;
57  T a1_, b1_, c1_;
58 
59 public:
60  RampTraj() = default;
61  void setLimit(T max_acc)
62  {
63  acc_ = max_acc;
64  }
65  void setState(T start, T end, T time_now)
66  {
67  start_ = start;
68  target_ = end;
69  time_start_ = time_now;
70  };
71  bool isReach(T t)
72  {
73  return (t >= time_total_ + time_start_);
74  }
75 
76  bool calc(T t)
77  {
78  if ((target_ - start_) < 0)
79  {
80  acc_ = -acc_;
81  }
83  if (abs(acc_) // if distant is too small
84  < abs(4. * (target_ - start_)) / (t * t))
85  {
86  return false;
87  }
89  sqrt(acc_ * acc_ * time_total_ * time_total_ - 4. * acc_ * (target_ - start_)) / abs(2. * acc_);
90  a0_ = start_;
91  b0_ = 0.;
92  c0_ = 0.5 * acc_;
93  a1_ = target_ - (acc_ * time_total_ * time_total_) / 2.;
94  b1_ = acc_ * time_total_;
95  c1_ = -0.5 * acc_;
96  speed_ = b0_ + 2. * c0_ * time_acc_;
97  return true;
98  };
99 
100  T getPos(T t)
101  {
103  if (t < 0.)
104  return start_;
105  else if (t > time_total_)
106  return target_;
107 
108  if (t <= time_total_)
109  {
110  if (t < time_acc_)
111  return a0_ + b0_ * t + c0_ * t * t;
112  else if (t < time_total_ - time_acc_)
113  return speed_ * (t - time_acc_) + a0_ + c0_ * (time_acc_ * time_acc_);
114  else
115  return a1_ + b1_ * t + c1_ * t * t;
116  }
117  else
118  return target_;
119  }
120 
121  T getVel(T t)
122  {
123  t -= time_start_;
124  if (t < 0. || t > time_total_)
125  return 0;
126 
127  if (t <= time_total_)
128  {
129  if (t < time_acc_)
130  return b0_ + 2. * c0_ * t;
131  else if (t < time_total_ - time_acc_)
132  return speed_;
133  else
134  return b1_ + 2. * c1_ * t;
135  }
136  else
137  return 0.;
138  }
139 
140  T getAcc(T t)
141  {
142  t -= time_start_;
143  if (t < 0. || t > time_total_)
144  return 0;
145 
146  if (t <= time_total_)
147  {
148  if (t < time_acc_)
149  return 2. * c0_;
150  else if (t < time_total_ - time_acc_)
151  return 0;
152  else
153  return 2. * c1_;
154  }
155  else
156  return 0.;
157  }
158 };
159 
160 // actually it is a controller
161 // ref: https://build-its-inprogress.blogspot.com/2017/12/controls-ramblings-how-to-get-from.html
162 template <typename T>
164 {
165 private:
166  T target_{};
167  T inertia_{};
168  T max_tau_{};
170  bool is_reach_{};
171 
172 public:
173  MinTimeTraj() = default;
174  void setLimit(T max_tau, T inertia, T tolerance)
175  {
176  max_tau_ = max_tau;
177  inertia_ = inertia;
178  tolerance_ = tolerance;
179  }
180 
181  void setTarget(T target)
182  {
183  target_ = target;
184  is_reach_ = false;
185  }
186  bool isReach()
187  {
188  return is_reach_;
189  }
190  T getTau(T pos, T vel)
191  {
192  T dx = pos - target_;
193  if (std::abs(dx) > tolerance_)
194  return max_tau_ * sgn(-max_tau_ * dx - 0.5 * inertia_ * vel * std::abs(vel));
195  else
196  {
197  is_reach_ = true;
198  return 0;
199  }
200  }
201 };
MinTimeTraj::getTau
T getTau(T pos, T vel)
Definition: traj_gen.h:190
MinTimeTraj::setLimit
void setLimit(T max_tau, T inertia, T tolerance)
Definition: traj_gen.h:174
RampTraj::getAcc
T getAcc(T t)
Definition: traj_gen.h:171
RampTraj::time_total_
T time_total_
Definition: traj_gen.h:81
MinTimeTraj::tolerance_
T tolerance_
Definition: traj_gen.h:169
RampTraj::a1_
T a1_
Definition: traj_gen.h:88
math_utilities.h
RampTraj::RampTraj
RampTraj()=default
RampTraj::b0_
T b0_
Definition: traj_gen.h:87
MinTimeTraj
Definition: traj_gen.h:163
RampTraj::a0_
T a0_
Definition: traj_gen.h:87
RampTraj::target_
T target_
Definition: traj_gen.h:80
RampTraj::b1_
T b1_
Definition: traj_gen.h:88
RampTraj::getPos
T getPos(T t)
Definition: traj_gen.h:131
MinTimeTraj::target_
T target_
Definition: traj_gen.h:166
sgn
int sgn(T val)
Definition: math_utilities.h:61
RampTraj::isReach
bool isReach(T t)
Definition: traj_gen.h:102
MinTimeTraj::max_tau_
T max_tau_
Definition: traj_gen.h:168
RampTraj::time_start_
T time_start_
Definition: traj_gen.h:83
start
ROSCPP_DECL void start()
RampTraj::c1_
T c1_
Definition: traj_gen.h:88
MinTimeTraj::inertia_
T inertia_
Definition: traj_gen.h:167
MinTimeTraj::isReach
bool isReach()
Definition: traj_gen.h:186
RampTraj::setState
void setState(T start, T end, T time_now)
Definition: traj_gen.h:96
RampTraj
Definition: traj_gen.h:45
RampTraj::acc_
T acc_
Definition: traj_gen.h:85
MinTimeTraj::setTarget
void setTarget(T target)
Definition: traj_gen.h:181
MinTimeTraj::MinTimeTraj
MinTimeTraj()=default
RampTraj::c0_
T c0_
Definition: traj_gen.h:87
MinTimeTraj::is_reach_
bool is_reach_
Definition: traj_gen.h:170
RampTraj::start_
T start_
Definition: traj_gen.h:79
RampTraj::setLimit
void setLimit(T max_acc)
Definition: traj_gen.h:92
RampTraj::speed_
T speed_
Definition: traj_gen.h:86
RampTraj::time_acc_
T time_acc_
Definition: traj_gen.h:82
t
geometry_msgs::TransformStamped t
RampTraj::calc
bool calc(T t)
Definition: traj_gen.h:107
RampTraj::getVel
T getVel(T t)
Definition: traj_gen.h:152


rm_common
Author(s):
autogenerated on Sun Apr 6 2025 02:22:01