gkouros / rsband_local_planner

A ROS move_base local planner plugin for Car-Like robots with Ackermann or 4-Wheel-Steering.
BSD 3-Clause "New" or "Revised" License
161 stars 51 forks source link

Compile errors with latest fuzzylite #9

Closed ksatyaki closed 6 years ago

ksatyaki commented 6 years ago

I was trying to use your planner. I get compile errors, however.

May be fuzzylite has changed a bit? If that is the case, could you please tell me which commit from fuzzylite to use?

Thanks.

[ 92%] Building CXX object rsband_local_planner/CMakeFiles/rsband_local_planner.dir/src/fuzzy_ptc.cpp.o
/home/chitt/workspace/cpp_ws/src/rsband_local_planner/src/fuzzy_ptc.cpp: In member function ‘void rsband_local_planner::FuzzyPTC::initializeFuzzyEngine()’:
/home/chitt/workspace/cpp_ws/src/rsband_local_planner/src/fuzzy_ptc.cpp:236:41: error: ‘class fl::Aggregated’ has no member named ‘setAccumulation’; did you mean ‘setAggregation’?
     frontSteeringAngle_->fuzzyOutput()->setAccumulation(fl::null);
                                         ^~~~~~~~~~~~~~~
/home/chitt/workspace/cpp_ws/src/rsband_local_planner/src/fuzzy_ptc.cpp:239:26: error: ‘class fl::OutputVariable’ has no member named ‘setLockPreviousOutputValue’; did you mean ‘setLockPreviousValue’?
     frontSteeringAngle_->setLockPreviousOutputValue(true);
                          ^~~~~~~~~~~~~~~~~~~~~~~~~~
/home/chitt/workspace/cpp_ws/src/rsband_local_planner/src/fuzzy_ptc.cpp:240:26: error: ‘class fl::OutputVariable’ has no member named ‘setLockOutputValueInRange’; did you mean ‘setLockValueInRange’?
     frontSteeringAngle_->setLockOutputValueInRange(false);
                          ^~~~~~~~~~~~~~~~~~~~~~~~~
/home/chitt/workspace/cpp_ws/src/rsband_local_planner/src/fuzzy_ptc.cpp:253:49: error: ‘class fl::Aggregated’ has no member named ‘setAccumulation’; did you mean ‘setAggregation’?
     rearSteeringDeviationAngle_->fuzzyOutput()->setAccumulation(fl::null);
                                                 ^~~~~~~~~~~~~~~
/home/chitt/workspace/cpp_ws/src/rsband_local_planner/src/fuzzy_ptc.cpp:255:58: error: no matching function for call to ‘fl::OutputVariable::setDefaultValue(const nullptr_t&)’
     rearSteeringDeviationAngle_->setDefaultValue(fl::null);
                                                          ^
In file included from /usr/local/include/fl/Headers.h:144:0,
                 from /home/chitt/workspace/cpp_ws/src/rsband_local_planner/include/rsband_local_planner/fuzzy_ptc.h:52,
                 from /home/chitt/workspace/cpp_ws/src/rsband_local_planner/src/fuzzy_ptc.cpp:38:
/usr/local/include/fl/variable/OutputVariable.h:153:22: note: candidate: virtual void fl::OutputVariable::setDefaultValue(fl::scalar)
         virtual void setDefaultValue(scalar defaultValue);
                      ^~~~~~~~~~~~~~~
/usr/local/include/fl/variable/OutputVariable.h:153:22: note:   no known conversion for argument 1 from ‘const nullptr_t {aka std::nullptr_t}’ to ‘fl::scalar {aka double}’
/home/chitt/workspace/cpp_ws/src/rsband_local_planner/src/fuzzy_ptc.cpp:256:34: error: ‘class fl::OutputVariable’ has no member named ‘setLockPreviousOutputValue’; did you mean ‘setLockPreviousValue’?
     rearSteeringDeviationAngle_->setLockPreviousOutputValue(true);
                                  ^~~~~~~~~~~~~~~~~~~~~~~~~~
/home/chitt/workspace/cpp_ws/src/rsband_local_planner/src/fuzzy_ptc.cpp:257:34: error: ‘class fl::OutputVariable’ has no member named ‘setLockOutputValueInRange’; did you mean ‘setLockValueInRange’?
     rearSteeringDeviationAngle_->setLockOutputValueInRange(false);
                                  ^~~~~~~~~~~~~~~~~~~~~~~~~
/home/chitt/workspace/cpp_ws/src/rsband_local_planner/src/fuzzy_ptc.cpp:271:28: error: ‘class fl::Aggregated’ has no member named ‘setAccumulation’; did you mean ‘setAggregation’?
     speed_->fuzzyOutput()->setAccumulation(fl::null);
                            ^~~~~~~~~~~~~~~
/home/chitt/workspace/cpp_ws/src/rsband_local_planner/src/fuzzy_ptc.cpp:297:68: error: no matching function for call to ‘fl::Engine::configure(const char [8], const char [8], const char [8], const char [8], const char [16])’
       "Minimum", "Maximum", "Minimum", "Maximum", "WeightedAverage");
                                                                    ^
In file included from /usr/local/include/fl/Headers.h:32:0,
                 from /home/chitt/workspace/cpp_ws/src/rsband_local_planner/include/rsband_local_planner/fuzzy_ptc.h:52,
                 from /home/chitt/workspace/cpp_ws/src/rsband_local_planner/src/fuzzy_ptc.cpp:38:
/usr/local/include/fl/Engine.h:78:22: note: candidate: virtual void fl::Engine::configure(const string&, const string&, const string&, const string&, const string&, const string&)
         virtual void configure(const std::string& conjunction,
                      ^~~~~~~~~
/usr/local/include/fl/Engine.h:78:22: note:   candidate expects 6 arguments, 5 provided
/usr/local/include/fl/Engine.h:102:22: note: candidate: virtual void fl::Engine::configure(fl::TNorm*, fl::SNorm*, fl::TNorm*, fl::SNorm*, fl::Defuzzifier*, fl::Activation*)
         virtual void configure(TNorm* conjunction, SNorm* disjunction,
                      ^~~~~~~~~
/usr/local/include/fl/Engine.h:102:22: note:   candidate expects 6 arguments, 5 provided
/home/chitt/workspace/cpp_ws/src/rsband_local_planner/src/fuzzy_ptc.cpp: In member function ‘bool rsband_local_planner::FuzzyPTC::computeVelocityCommands(const std::vector<geometry_msgs::PoseStamped_<std::allocator<void> > >&, geometry_msgs::Twist&)’:
/home/chitt/workspace/cpp_ws/src/rsband_local_planner/src/fuzzy_ptc.cpp:333:29: error: ‘class fl::InputVariable’ has no member named ‘setInputValue’; did you mean ‘fuzzyInputValue’?
     angularDeviationError_->setInputValue(rad2deg(ea));
                             ^~~~~~~~~~~~~
/home/chitt/workspace/cpp_ws/src/rsband_local_planner/src/fuzzy_ptc.cpp:334:24: error: ‘class fl::InputVariable’ has no member named ‘setInputValue’; did you mean ‘fuzzyInputValue’?
     orientationError_->setInputValue(rad2deg(eo));
                        ^~~~~~~~~~~~~
/home/chitt/workspace/cpp_ws/src/rsband_local_planner/src/fuzzy_ptc.cpp:335:21: error: ‘class fl::InputVariable’ has no member named ‘setInputValue’; did you mean ‘fuzzyInputValue’?
     positionError_->setInputValue(ep);
                     ^~~~~~~~~~~~~
/home/chitt/workspace/cpp_ws/src/rsband_local_planner/src/fuzzy_ptc.cpp:336:29: error: ‘class fl::InputVariable’ has no member named ‘setInputValue’; did you mean ‘fuzzyInputValue’?
     lateralDeviationError_->setInputValue(ey);
                             ^~~~~~~~~~~~~
/home/chitt/workspace/cpp_ws/src/rsband_local_planner/src/fuzzy_ptc.cpp:337:17: error: ‘class fl::InputVariable’ has no member named ‘setInputValue’; did you mean ‘fuzzyInputValue’?
     direction_->setInputValue(drcn);
                 ^~~~~~~~~~~~~
/home/chitt/workspace/cpp_ws/src/rsband_local_planner/src/fuzzy_ptc.cpp:341:33: error: ‘class fl::OutputVariable’ has no member named ‘getOutputValue’; did you mean ‘getDefaultValue’?
     double vel = drcn * speed_->getOutputValue();  // linear velocity
                                 ^~~~~~~~~~~~~~
/home/chitt/workspace/cpp_ws/src/rsband_local_planner/src/fuzzy_ptc.cpp:342:47: error: ‘class fl::OutputVariable’ has no member named ‘getOutputValue’; did you mean ‘getDefaultValue’?
     double fsa = deg2rad(frontSteeringAngle_->getOutputValue());  // front steering angle
                                               ^~~~~~~~~~~~~~
/home/chitt/workspace/cpp_ws/src/rsband_local_planner/src/fuzzy_ptc.cpp:355:52: error: ‘class fl::OutputVariable’ has no member named ‘getOutputValue’; did you mean ‘getDefaultValue’?
         rsa = deg2rad(rearSteeringDeviationAngle_->getOutputValue());
                                                    ^~~~~~~~~~~~~~
/home/chitt/workspace/cpp_ws/src/rsband_local_planner/src/fuzzy_ptc.cpp:358:59: error: ‘class fl::OutputVariable’ has no member named ‘getOutputValue’; did you mean ‘getDefaultValue’?
         rsa = -fsa + deg2rad(rearSteeringDeviationAngle_->getOutputValue());
gkouros commented 6 years ago

Hi ksatyaki,

The planner has been tested only on ROS Indigo with fuzzylite-5 (https://github.com/fuzzylite/fuzzylite/tree/fuzzylite-5.x).

Hope that helps. If you still can't build the planner let me know.

Regards, George

gkouros commented 6 years ago

I've added a new branch for ROS Kinetic with Fuzzylite-6.0 that compiles without issues.