38 #ifndef RSBAND_LOCAL_PLANNER_FUZZY_PTC_H
39 #define RSBAND_LOCAL_PLANNER_FUZZY_PTC_H
43 #include <geometry_msgs/Pose.h>
44 #include <geometry_msgs/Twist.h>
45 #include <nav_msgs/Path.h>
46 #include <visualization_msgs/Marker.h>
49 #include "rsband_local_planner/RSBandPlannerConfig.h"
52 #include <fl/Headers.h>
55 namespace rsband_local_planner
88 const std::vector<geometry_msgs::PoseStamped>& path,
89 geometry_msgs::Twist& cmd);
96 bool isGoalReached(
const std::vector<geometry_msgs::PoseStamped>& path);
120 const std::vector<geometry_msgs::PoseStamped>& path,
121 unsigned int subGoalIdx);
131 const std::vector<geometry_msgs::PoseStamped>& path,
132 unsigned int subGoalIdx);
141 const std::vector<geometry_msgs::PoseStamped>& path,
142 unsigned int subGoalIdx);
151 const std::vector<geometry_msgs::PoseStamped>& path,
152 unsigned int subGoalIdx);
162 const std::vector<geometry_msgs::PoseStamped>& path,
163 unsigned int idx1,
unsigned int idx2);
171 const std::vector<geometry_msgs::PoseStamped>& path);
180 const std::vector<geometry_msgs::PoseStamped>& path,
255 #endif // RSBAND_LOCAL_PLANNER_FUZZY_PTC_H
fl::OutputVariable * frontSteeringAngle_
steering angle output variable 1
fl::InputVariable * direction_
direction (forwards/backwards) input variable
unsigned int findSubGoal(const std::vector< geometry_msgs::PoseStamped > &path)
Finds the current sub goal to follow.
Path tracking controller for car like robots, based on fuzzy logic.
fl::RuleBlock * ruleBlock_
flc rule block
fl::InputVariable * lateralDeviationError_
lateral deviation error
ros::Publisher subGoalPub_
publisher of the current sub goal marker
double maxSteeringAngle_
the max steering angle of the virtual middle wheel
double calcAngularDeviationError(const std::vector< geometry_msgs::PoseStamped > &path, unsigned int subGoalIdx)
Calculates angular deviation from subgoal.
double calcPositionError(const std::vector< geometry_msgs::PoseStamped > &path, unsigned int subGoalIdx)
Calculates the distance between the robot and the sub goal.
double calcOrientationError(const std::vector< geometry_msgs::PoseStamped > &path, unsigned int subGoalIdx)
Calculates the orientation error between the robot and the sub goal.
visualization_msgs::Marker subGoal_
sub goal visualization marker
void reconfigure(RSBandPlannerConfig &config)
Reconfigures controller params.
fl::OutputVariable * speed_
speed output variable
double yawGoalTolerance_
yaw goal tolerance
fl::InputVariable * positionError_
robot to goal distance error input variable
std::vector< std::string > frontSteeringRules_
front steering rules
std::vector< std::string > rearSteeringDeviationRules_
rear steering deviation rules
bool initialized_
variable indicating whether the controller has been initialized
FuzzyPTC(std::string name)
double calcLateralDeviationError(const std::vector< geometry_msgs::PoseStamped > &path, unsigned int subGoalIdx)
Calculates the lateral deviation from the sub goal.
double calcDistance(const std::vector< geometry_msgs::PoseStamped > &path, unsigned int idx1, unsigned int idx2)
Calculates the distance between two path waypoints.
ros::NodeHandle * pnh_
private ros node handle
fl::InputVariable * angularDeviationError_
robot to goal direction orientation error input variable
void initialize()
Initializes controller.
fl::InputVariable * orientationError_
robot to final goal orientation error input variable
double updateSubGoalDistThreshold_
subGoal step
fl::OutputVariable * rearSteeringDeviationAngle_
rear steering deviation angle output variable
double goalDistThreshold_
distance to goal threshold
RearSteeringMode rearSteeringMode_
rear wheel steering mode (none/counter/crab/hybrid)
double xyGoalTolerance_
xy goal tolerance threshold
RearSteeringMode
rear steering mode enum
void initializeFuzzyEngine()
Initializes fuzzy engine.
bool isCuspPoint(const std::vector< geometry_msgs::PoseStamped > &path, unsigned int idx)
Checks whether a path waypoint is a cusp point.
bool isGoalReached(const std::vector< geometry_msgs::PoseStamped > &path)
Checks if the goal position and orientation have been reached.
double maxSpeed_
max speed
bool stop_
if true controller returns zero velocity commands
bool computeVelocityCommands(const std::vector< geometry_msgs::PoseStamped > &path, geometry_msgs::Twist &cmd)
Computes velocity commands.
std::vector< std::string > speedRules_
speed rules
fl::Engine * engine_
position FLC engine
double wheelbase_
the robot wheelbase
double latDevTolerance_
lateral deviation tolerance
bool displayControllerIO_
display current trajectory information