38 #ifndef OSCILLATION_COST_FUNCTION_H_ 39 #define OSCILLATION_COST_FUNCTION_H_
void resetOscillationFlags()
Reset the oscillation flags for the local planner.
virtual ~OscillationCostFunction()
geometry_msgs::TransformStamped t
double oscillation_reset_dist_
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
double scoreTrajectory(Trajectory &traj)
OscillationCostFunction()
Eigen::Vector3f prev_stationary_pos_
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...
double oscillation_reset_angle_
void resetOscillationFlagsIfPossible(const Eigen::Vector3f &pos, const Eigen::Vector3f &prev)
Provides an interface for critics of trajectories During each sampling run, a batch of many trajector...
Holds a trajectory generated by considering an x, y, and theta velocity.
void updateOscillationFlags(Eigen::Vector3f pos, base_local_planner::Trajectory *traj, double min_vel_trans)
void setOscillationResetDist(double dist, double angle)