oscillation_cost_function.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2008, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage, Inc. nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * Author: TKruse
36  *********************************************************************/
37 
39 
40 #include <cmath>
41 
42 namespace base_local_planner {
43 
45 }
46 
48  prev_stationary_pos_ = Eigen::Vector3f::Zero();
49 }
50 
51 void OscillationCostFunction::setOscillationResetDist(double dist, double angle) {
54 }
55 
56 void OscillationCostFunction::updateOscillationFlags(Eigen::Vector3f pos, base_local_planner::Trajectory* traj, double min_vel_trans) {
57  if (traj->cost_ >= 0) {
58  if (setOscillationFlags(traj, min_vel_trans)) {
60  }
61  //if we've got restrictions... check if we can reset any oscillation flags
66  }
67  }
68 }
69 
70 void OscillationCostFunction::resetOscillationFlagsIfPossible(const Eigen::Vector3f& pos, const Eigen::Vector3f& prev) {
71  double x_diff = pos[0] - prev[0];
72  double y_diff = pos[1] - prev[1];
73  double sq_dist = x_diff * x_diff + y_diff * y_diff;
74 
75  double th_diff = pos[2] - prev[2];
76 
77  //if we've moved far enough... we can reset our flags
79  fabs(th_diff) > oscillation_reset_angle_) {
81  }
82 }
83 
85  strafe_pos_only_ = false;
87  strafing_pos_ = false;
88  strafing_neg_ = false;
89 
90  rot_pos_only_ = false;
91  rot_neg_only_ = false;
92  rotating_pos_ = false;
93  rotating_neg_ = false;
94 
95  forward_pos_only_ = false;
96  forward_neg_only_ = false;
97  forward_pos_ = false;
98  forward_neg_ = false;
99 }
100 
102  bool flag_set = false;
103  //set oscillation flags for moving forward and backward
104  if (t->xv_ < 0.0) {
106  forward_neg_only_ = true;
107  flag_set = true;
108  }
109  forward_pos_ = false;
110  forward_neg_ = true;
111  }
112  if (t->xv_ > 0.0) {
113  if (forward_neg_) {
114  forward_pos_only_ = true;
115  flag_set = true;
116  }
117  forward_neg_ = false;
118  forward_pos_ = true;
119  }
120 
121  //we'll only set flags for strafing and rotating when we're not moving forward at all
122  if (fabs(t->xv_) <= min_vel_trans) {
123  //check negative strafe
124  if (t->yv_ < 0) {
125  if (strafing_pos_) {
126  strafe_neg_only_ = true;
127  flag_set = true;
128  }
129  strafing_pos_ = false;
130  strafing_neg_ = true;
131  }
132 
133  //check positive strafe
134  if (t->yv_ > 0) {
135  if (strafing_neg_) {
137  flag_set = true;
138  }
139  strafing_neg_ = false;
140  strafing_pos_ = true;
141  }
142 
143  //check negative rotation
144  if (t->thetav_ < 0) {
145  if (rotating_pos_) {
146  rot_neg_only_ = true;
147  flag_set = true;
148  }
149  rotating_pos_ = false;
150  rotating_neg_ = true;
151  }
152 
153  //check positive rotation
154  if (t->thetav_ > 0) {
155  if (rotating_neg_) {
156  rot_pos_only_ = true;
157  flag_set = true;
158  }
159  rotating_neg_ = false;
160  rotating_pos_ = true;
161  }
162  }
163  return flag_set;
164 }
165 
166 double OscillationCostFunction::scoreTrajectory(Trajectory &traj) {
167  if ((forward_pos_only_ && traj.xv_ < 0.0) ||
168  (forward_neg_only_ && traj.xv_ > 0.0) ||
169  (strafe_pos_only_ && traj.yv_ < 0.0) ||
170  (strafe_neg_only_ && traj.yv_ > 0.0) ||
171  (rot_pos_only_ && traj.thetav_ < 0.0) ||
172  (rot_neg_only_ && traj.thetav_ > 0.0)) {
173  return -5.0;
174  }
175  return 0.0;
176 }
177 
178 } /* namespace base_local_planner */
base_local_planner::OscillationCostFunction::strafing_pos_
bool strafing_pos_
Definition: oscillation_cost_function.h:148
angle
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
base_local_planner::OscillationCostFunction::setOscillationFlags
bool setOscillationFlags(base_local_planner::Trajectory *t, double min_vel_trans)
Given a trajectory that's selected, set flags if needed to prevent the robot from oscillating.
Definition: oscillation_cost_function.cpp:136
base_local_planner::OscillationCostFunction::strafe_pos_only_
bool strafe_pos_only_
Definition: oscillation_cost_function.h:148
base_local_planner::OscillationCostFunction::forward_neg_only_
bool forward_neg_only_
Definition: oscillation_cost_function.h:150
base_local_planner::OscillationCostFunction::updateOscillationFlags
void updateOscillationFlags(Eigen::Vector3f pos, base_local_planner::Trajectory *traj, double min_vel_trans)
Definition: oscillation_cost_function.cpp:91
base_local_planner::OscillationCostFunction::rotating_neg_
bool rotating_neg_
Definition: oscillation_cost_function.h:149
base_local_planner::OscillationCostFunction::rot_neg_only_
bool rot_neg_only_
Definition: oscillation_cost_function.h:149
base_local_planner::OscillationCostFunction::oscillation_reset_angle_
double oscillation_reset_angle_
Definition: oscillation_cost_function.h:153
base_local_planner::OscillationCostFunction::forward_neg_
bool forward_neg_
Definition: oscillation_cost_function.h:150
base_local_planner::OscillationCostFunction::scoreTrajectory
double scoreTrajectory(Trajectory &traj)
Definition: oscillation_cost_function.cpp:201
base_local_planner::OscillationCostFunction::strafing_neg_
bool strafing_neg_
Definition: oscillation_cost_function.h:148
base_local_planner::OscillationCostFunction::rot_pos_only_
bool rot_pos_only_
Definition: oscillation_cost_function.h:149
base_local_planner::OscillationCostFunction::~OscillationCostFunction
virtual ~OscillationCostFunction()
Definition: oscillation_cost_function.cpp:82
base_local_planner::OscillationCostFunction::oscillation_reset_dist_
double oscillation_reset_dist_
Definition: oscillation_cost_function.h:153
base_local_planner::Trajectory::cost_
double cost_
The cost/score of the trajectory.
Definition: trajectory.h:94
base_local_planner::OscillationCostFunction::prev_stationary_pos_
Eigen::Vector3f prev_stationary_pos_
Definition: oscillation_cost_function.h:155
base_local_planner::OscillationCostFunction::rotating_pos_
bool rotating_pos_
Definition: oscillation_cost_function.h:149
base_local_planner::OscillationCostFunction::strafe_neg_only_
bool strafe_neg_only_
Definition: oscillation_cost_function.h:148
base_local_planner::OscillationCostFunction::OscillationCostFunction
OscillationCostFunction()
Definition: oscillation_cost_function.cpp:79
base_local_planner::OscillationCostFunction::resetOscillationFlags
void resetOscillationFlags()
Reset the oscillation flags for the local planner.
Definition: oscillation_cost_function.cpp:119
base_local_planner::OscillationCostFunction::forward_pos_
bool forward_pos_
Definition: oscillation_cost_function.h:150
oscillation_cost_function.h
base_local_planner::OscillationCostFunction::setOscillationResetDist
void setOscillationResetDist(double dist, double angle)
Definition: oscillation_cost_function.cpp:86
base_local_planner::Trajectory
Holds a trajectory generated by considering an x, y, and theta velocity.
Definition: trajectory.h:76
base_local_planner::OscillationCostFunction::forward_pos_only_
bool forward_pos_only_
Definition: oscillation_cost_function.h:150
base_local_planner
Definition: costmap_model.h:44
base_local_planner::OscillationCostFunction::resetOscillationFlagsIfPossible
void resetOscillationFlagsIfPossible(const Eigen::Vector3f &pos, const Eigen::Vector3f &prev)
Definition: oscillation_cost_function.cpp:105
t
geometry_msgs::TransformStamped t


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