fuzzy_ptc.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2016, George Kouros.
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 the the copyright holder 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: George Kouros
36  *********************************************************************/
37 
38 #ifndef RSBAND_LOCAL_PLANNER_FUZZY_PTC_H
39 #define RSBAND_LOCAL_PLANNER_FUZZY_PTC_H
40 
41 // ros related libraries
42 #include <ros/ros.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>
47 
48 // dynamic reconfigure configuration
49 #include "rsband_local_planner/RSBandPlannerConfig.h"
50 
51 // fuzzylite headers
52 #include <fl/Headers.h>
53 
54 
55 namespace rsband_local_planner
56 {
57 
62  class FuzzyPTC
63  {
64  public:
65  /*
66  * @brief Constructor
67  * @param name: Name used to load the paramaters of the controller
68  */
69  FuzzyPTC(std::string name);
70 
74  ~FuzzyPTC();
75 
79  void reconfigure(RSBandPlannerConfig& config);
80 
88  const std::vector<geometry_msgs::PoseStamped>& path,
89  geometry_msgs::Twist& cmd);
90 
96  bool isGoalReached(const std::vector<geometry_msgs::PoseStamped>& path);
97 
100 
101  private:
102 
106  void initialize();
107 
111  void initializeFuzzyEngine();
112 
120  const std::vector<geometry_msgs::PoseStamped>& path,
121  unsigned int subGoalIdx);
122 
130  double calcOrientationError(
131  const std::vector<geometry_msgs::PoseStamped>& path,
132  unsigned int subGoalIdx);
133 
140  double calcPositionError(
141  const std::vector<geometry_msgs::PoseStamped>& path,
142  unsigned int subGoalIdx);
143 
151  const std::vector<geometry_msgs::PoseStamped>& path,
152  unsigned int subGoalIdx);
153 
161  double calcDistance(
162  const std::vector<geometry_msgs::PoseStamped>& path,
163  unsigned int idx1, unsigned int idx2);
164 
170  unsigned int findSubGoal(
171  const std::vector<geometry_msgs::PoseStamped>& path);
172 
179  bool isCuspPoint(
180  const std::vector<geometry_msgs::PoseStamped>& path,
181  unsigned int idx);
182 
183 
185  ros::NodeHandle* pnh_;
186 
189 
191  ros::Publisher subGoalPub_;
193  visualization_msgs::Marker subGoal_;
194 
197 
199  double wheelbase_;
203  double maxSpeed_;
217  bool stop_;
218 
219  // fuzzylite related variables
220 
222  fl::Engine* engine_;
223 
225  fl::InputVariable* direction_;
227  fl::InputVariable* angularDeviationError_;
229  fl::InputVariable* orientationError_;
231  fl::InputVariable* positionError_;
233  fl::InputVariable* lateralDeviationError_;
235  fl::OutputVariable* frontSteeringAngle_;
237  fl::OutputVariable* rearSteeringDeviationAngle_;
239  fl::OutputVariable* speed_;
240 
242  fl::RuleBlock* ruleBlock_;
243 
245  std::vector<std::string> speedRules_;
247  std::vector<std::string> frontSteeringRules_;
249  std::vector<std::string> rearSteeringDeviationRules_;
250 
251  };
252 
253 }
254 
255 #endif // RSBAND_LOCAL_PLANNER_FUZZY_PTC_H
fl::OutputVariable * frontSteeringAngle_
steering angle output variable 1
Definition: fuzzy_ptc.h:235
fl::InputVariable * direction_
direction (forwards/backwards) input variable
Definition: fuzzy_ptc.h:225
unsigned int findSubGoal(const std::vector< geometry_msgs::PoseStamped > &path)
Finds the current sub goal to follow.
Definition: fuzzy_ptc.cpp:462
Path tracking controller for car like robots, based on fuzzy logic.
Definition: fuzzy_ptc.h:62
fl::RuleBlock * ruleBlock_
flc rule block
Definition: fuzzy_ptc.h:242
fl::InputVariable * lateralDeviationError_
lateral deviation error
Definition: fuzzy_ptc.h:233
ros::Publisher subGoalPub_
publisher of the current sub goal marker
Definition: fuzzy_ptc.h:191
double maxSteeringAngle_
the max steering angle of the virtual middle wheel
Definition: fuzzy_ptc.h:201
double calcAngularDeviationError(const std::vector< geometry_msgs::PoseStamped > &path, unsigned int subGoalIdx)
Calculates angular deviation from subgoal.
Definition: fuzzy_ptc.cpp:415
double calcPositionError(const std::vector< geometry_msgs::PoseStamped > &path, unsigned int subGoalIdx)
Calculates the distance between the robot and the sub goal.
Definition: fuzzy_ptc.cpp:432
double calcOrientationError(const std::vector< geometry_msgs::PoseStamped > &path, unsigned int subGoalIdx)
Calculates the orientation error between the robot and the sub goal.
Definition: fuzzy_ptc.cpp:424
visualization_msgs::Marker subGoal_
sub goal visualization marker
Definition: fuzzy_ptc.h:193
void reconfigure(RSBandPlannerConfig &config)
Reconfigures controller params.
Definition: fuzzy_ptc.cpp:131
fl::OutputVariable * speed_
speed output variable
Definition: fuzzy_ptc.h:239
double yawGoalTolerance_
yaw goal tolerance
Definition: fuzzy_ptc.h:207
fl::InputVariable * positionError_
robot to goal distance error input variable
Definition: fuzzy_ptc.h:231
std::vector< std::string > frontSteeringRules_
front steering rules
Definition: fuzzy_ptc.h:247
std::vector< std::string > rearSteeringDeviationRules_
rear steering deviation rules
Definition: fuzzy_ptc.h:249
bool initialized_
variable indicating whether the controller has been initialized
Definition: fuzzy_ptc.h:188
FuzzyPTC(std::string name)
Definition: fuzzy_ptc.cpp:62
double calcLateralDeviationError(const std::vector< geometry_msgs::PoseStamped > &path, unsigned int subGoalIdx)
Calculates the lateral deviation from the sub goal.
Definition: fuzzy_ptc.cpp:440
double calcDistance(const std::vector< geometry_msgs::PoseStamped > &path, unsigned int idx1, unsigned int idx2)
Calculates the distance between two path waypoints.
Definition: fuzzy_ptc.cpp:449
ros::NodeHandle * pnh_
private ros node handle
Definition: fuzzy_ptc.h:185
fl::InputVariable * angularDeviationError_
robot to goal direction orientation error input variable
Definition: fuzzy_ptc.h:227
void initialize()
Initializes controller.
Definition: fuzzy_ptc.cpp:77
fl::InputVariable * orientationError_
robot to final goal orientation error input variable
Definition: fuzzy_ptc.h:229
double updateSubGoalDistThreshold_
subGoal step
Definition: fuzzy_ptc.h:213
fl::OutputVariable * rearSteeringDeviationAngle_
rear steering deviation angle output variable
Definition: fuzzy_ptc.h:237
double goalDistThreshold_
distance to goal threshold
Definition: fuzzy_ptc.h:209
RearSteeringMode rearSteeringMode_
rear wheel steering mode (none/counter/crab/hybrid)
Definition: fuzzy_ptc.h:196
double xyGoalTolerance_
xy goal tolerance threshold
Definition: fuzzy_ptc.h:205
RearSteeringMode
rear steering mode enum
Definition: fuzzy_ptc.h:99
void initializeFuzzyEngine()
Initializes fuzzy engine.
Definition: fuzzy_ptc.cpp:151
bool isCuspPoint(const std::vector< geometry_msgs::PoseStamped > &path, unsigned int idx)
Checks whether a path waypoint is a cusp point.
Definition: fuzzy_ptc.cpp:488
bool isGoalReached(const std::vector< geometry_msgs::PoseStamped > &path)
Checks if the goal position and orientation have been reached.
Definition: fuzzy_ptc.cpp:404
double maxSpeed_
max speed
Definition: fuzzy_ptc.h:203
bool stop_
if true controller returns zero velocity commands
Definition: fuzzy_ptc.h:217
bool computeVelocityCommands(const std::vector< geometry_msgs::PoseStamped > &path, geometry_msgs::Twist &cmd)
Computes velocity commands.
Definition: fuzzy_ptc.cpp:306
std::vector< std::string > speedRules_
speed rules
Definition: fuzzy_ptc.h:245
fl::Engine * engine_
position FLC engine
Definition: fuzzy_ptc.h:222
double wheelbase_
the robot wheelbase
Definition: fuzzy_ptc.h:199
double latDevTolerance_
lateral deviation tolerance
Definition: fuzzy_ptc.h:211
bool displayControllerIO_
display current trajectory information
Definition: fuzzy_ptc.h:215


rsband_local_planner
Author(s): George Kouros
autogenerated on Wed Nov 9 2016 19:13:53