Giter Site home page Giter Site logo

gkouros / rsband_local_planner Goto Github PK

View Code? Open in Web Editor NEW
152.0 6.0 51.0 932 KB

A ROS move_base local planner plugin for Car-Like robots with Ackermann or 4-Wheel-Steering.

License: BSD 3-Clause "New" or "Revised" License

CMake 1.88% C++ 92.45% Python 5.67%
car-like-robots robotics navigation collision-avoidance four-wheel-steering fuzzy-path-tracking reeds-shepp-planner ompl fuzzylite move-base-plugin

rsband_local_planner's Introduction

rsband_local_planner

The rsband_local_planner combines an elastic band planner, a reeds shepp planner and a fuzzy logic based path tracking controller, to achieve reactive local planning for Car-Like robots with Ackermann or 4-Wheel-Steering.

Important Dependencies

  • eband_local_planner: Elastic Band Algorithm implementation used to dynamically deform the global path
  • OMPL: Motion planning library, that contains a Reeds-Shepp State Space used in the Reeds-Shepp Path Planner
  • fuzzylite: Fuzzy logic control library, used in the fuzzy path tracking controller

How to install fuzzylite

$ git clone [email protected]:fuzzylite/fuzzylite.git
$ cd fuzzylite/fuzzylite
$ git checkout fuzzylite-6.x
$ mkdir build && cd build
$ cmake ..
$ make
$ sudo make install

References

  • M. Khatib et al. “Dynamic path modification for car-like nonholonomic mobile robots”. In: Robotics and Automation, 1997. Proceedings., 1997 IEEE International Conference on. Vol. 4. Apr. 1997, 2920–2925 vol.4. DOI: 10.1109/ROBOT.1997.606730

rsband_local_planner's People

Contributors

gkouros avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar

rsband_local_planner's Issues

Can't get velocity out of fuzzylite

Hi,

I am experimenting with your controller but I don't get any velocities out of it.
See here an output:

Ea: 23.224841, Eo: 28.349788, Ep: 5.055443, Ey: 1.993565 [ INFO] [1515160524.377827833, 8.000000000]: vel: 0.000, front steering angle: 14.324, ready: 1, status:

I didn't change any of your fuzzy rules, all default.
Steering angle looks plausible, but I don't know what I am missing.

catkin_make error

Hi,gkouros!
when I used catkin_make to build the project,I encountered these errors.
I should already have installed all the dependecies.

catkin_make
Base path: /home/nvidia/planner_ws
Source space: /home/nvidia/planner_ws/src
Build space: /home/nvidia/planner_ws/build
Devel space: /home/nvidia/planner_ws/devel
Install space: /home/nvidia/planner_ws/install

Running command: "make cmake_check_build_system" in "/home/nvidia/planner_ws/build"

Running command: "make -j4 -l4" in "/home/nvidia/planner_ws/build"

[ 20%] Built target rsband_local_planner_gencfg
[ 40%] Building CXX object rsband_local_planner/CMakeFiles/rsband_local_planner.dir/src/rsband_local_planner_ros.cpp.o
/home/nvidia/planner_ws/src/rsband_local_planner/src/rsband_local_planner_ros.cpp: In member function ‘void rsband_local_planner::RSBandPlannerROS::ebandReconfigureCallback(eband_local_planner::EBandPlannerConfig&, uint32_t)’:
/home/nvidia/planner_ws/src/rsband_local_planner/src/rsband_local_planner_ros.cpp:141:22: error: ‘class eband_local_planner::EBandPlanner’ has no member named ‘reconfigure’
ebandPlanner_->reconfigure(config);
^
/home/nvidia/planner_ws/src/rsband_local_planner/src/rsband_local_planner_ros.cpp: In member function ‘virtual bool rsband_local_planner::RSBandPlannerROS::setPlan(const std::vector<geometry_msgs::PoseStamped_<std::allocator > >&)’:
/home/nvidia/planner_ws/src/rsband_local_planner/src/rsband_local_planner_ros.cpp:164:29: error: invalid initialization of reference of type ‘const tf::TransformListener&’ from expression of type ‘tf2_ros::Buffer’
planStartEndCounters))
^
In file included from /opt/ros/kinetic/include/eband_local_planner/eband_local_planner.h:47:0,
from /home/nvidia/planner_ws/src/rsband_local_planner/include/rsband_local_planner/rsband_local_planner_ros.h:48,
from /home/nvidia/planner_ws/src/rsband_local_planner/src/rsband_local_planner_ros.cpp:38:
/opt/ros/kinetic/include/eband_local_planner/conversions_and_types.h:99:8: note: in passing argument 1 of ‘bool eband_local_planner::transformGlobalPlan(const tf::TransformListener&, const std::vector<geometry_msgs::PoseStamped_<std::allocator > >&, costmap_2d::Costmap2DROS&, const string&, std::vector<geometry_msgs::PoseStamped_<std::allocator > >&, std::vector&)’
bool transformGlobalPlan(const tf::TransformListener& tf, const std::vector<g
^
/home/nvidia/planner_ws/src/rsband_local_planner/src/rsband_local_planner_ros.cpp: In member function ‘virtual bool rsband_local_planner::RSBandPlannerROS::isGoalReached()’:
/home/nvidia/planner_ws/src/rsband_local_planner/src/rsband_local_planner_ros.cpp:348:45: error: no matching function for call to ‘costmap_2d::Costmap2DROS::getRobotPose(geometry_msgs::PoseStamped&)’
if (!costmapROS_->getRobotPose(robotPose))
^
In file included from /opt/ros/kinetic/include/nav_core/base_local_planner.h:42:0,
from /home/nvidia/planner_ws/src/rsband_local_planner/include/rsband_local_planner/rsband_local_planner_ros.h:47,
from /home/nvidia/planner_ws/src/rsband_local_planner/src/rsband_local_planner_ros.cpp:38:
/opt/ros/kinetic/include/costmap_2d/costmap_2d_ros.h:123:8: note: candidate: bool costmap_2d::Costmap2DROS::getRobotPose(tf::Stampedtf::Transform&) const
bool getRobotPose(tf::Stampedtf::Pose& global_pose) const;
^
/opt/ros/kinetic/include/costmap_2d/costmap_2d_ros.h:123:8: note: no known conversion for argument 1 from ‘geometry_msgs::PoseStamped {aka geometry_msgs::PoseStamped_<std::allocator >}’ to ‘tf::Stampedtf::Transform&’
/home/nvidia/planner_ws/src/rsband_local_planner/src/rsband_local_planner_ros.cpp:357:60: error: invalid initialization of reference of type ‘const tf::Stampedtf::Transform&’ from expression of type ‘geometry_msgs::PoseStamped {aka geometry_msgs::PoseStamped_<std::allocator >}’
robotPose, goal.pose.position.x, goal.pose.position.y);
^
In file included from /home/nvidia/planner_ws/src/rsband_local_planner/src/rsband_local_planner_ros.cpp:40:0:
/opt/ros/kinetic/include/base_local_planner/goal_functions.h:65:10: note: in passing argument 1 of ‘double base_local_planner::getGoalPositionDistance(const tf::Stampedtf::Transform&, double, double)’
double getGoalPositionDistance(const tf::Stampedtf::Pose& global_pose, doub
^
/home/nvidia/planner_ws/src/rsband_local_planner/src/rsband_local_planner_ros.cpp:359:51: error: invalid initialization of reference of type ‘const tf::Stampedtf::Transform&’ from expression of type ‘geometry_msgs::PoseStamped {aka geometry_msgs::PoseStamped_<std::allocator >}’
robotPose, tf::getYaw(goal.pose.orientation));
^
In file included from /home/nvidia/planner_ws/src/rsband_local_planner/src/rsband_local_planner_ros.cpp:40:0:
/opt/ros/kinetic/include/base_local_planner/goal_functions.h:74:10: note: in passing argument 1 of ‘double base_local_planner::getGoalOrientationAngleDifference(const tf::Stampedtf::Transform&, double)’
double getGoalOrientationAngleDifference(const tf::Stampedtf::Pose& global_
^
/home/nvidia/planner_ws/src/rsband_local_planner/src/rsband_local_planner_ros.cpp: In member function ‘bool rsband_local_planner::RSBandPlannerROS::updateEBand()’:
/home/nvidia/planner_ws/src/rsband_local_planner/src/rsband_local_planner_ros.cpp:381:45: error: no matching function for call to ‘costmap_2d::Costmap2DROS::getRobotPose(geometry_msgs::PoseStamped&)’
if (!costmapROS_->getRobotPose(robotPose))
^
In file included from /opt/ros/kinetic/include/nav_core/base_local_planner.h:42:0,
from /home/nvidia/planner_ws/src/rsband_local_planner/include/rsband_local_planner/rsband_local_planner_ros.h:47,
from /home/nvidia/planner_ws/src/rsband_local_planner/src/rsband_local_planner_ros.cpp:38:
/opt/ros/kinetic/include/costmap_2d/costmap_2d_ros.h:123:8: note: candidate: bool costmap_2d::Costmap2DROS::getRobotPose(tf::Stampedtf::Transform&) const
bool getRobotPose(tf::Stampedtf::Pose& global_pose) const;
^
/opt/ros/kinetic/include/costmap_2d/costmap_2d_ros.h:123:8: note: no known conversion for argument 1 from ‘geometry_msgs::PoseStamped {aka geometry_msgs::PoseStamped_<std::allocator >}’ to ‘tf::Stampedtf::Transform&’
/home/nvidia/planner_ws/src/rsband_local_planner/src/rsband_local_planner_ros.cpp:402:29: error: invalid initialization of reference of type ‘const tf::TransformListener&’ from expression of type ‘tf2_ros::Buffer’
planStartEndCounters))
^
In file included from /opt/ros/kinetic/include/eband_local_planner/eband_local_planner.h:47:0,
from /home/nvidia/planner_ws/src/rsband_local_planner/include/rsband_local_planner/rsband_local_planner_ros.h:48,
from /home/nvidia/planner_ws/src/rsband_local_planner/src/rsband_local_planner_ros.cpp:38:
/opt/ros/kinetic/include/eband_local_planner/conversions_and_types.h:99:8: note: in passing argument 1 of ‘bool eband_local_planner::transformGlobalPlan(const tf::TransformListener&, const std::vector<geometry_msgs::PoseStamped_<std::allocator > >&, costmap_2d::Costmap2DROS&, const string&, std::vector<geometry_msgs::PoseStamped_<std::allocator > >&, std::vector&)’
bool transformGlobalPlan(const tf::TransformListener& tf, const std::vector<g
^
In file included from /opt/ros/kinetic/include/class_loader/class_loader_core.hpp:46:0,
from /opt/ros/kinetic/include/class_loader/class_loader.hpp:43,
from /opt/ros/kinetic/include/class_loader/./multi_library_class_loader.hpp:42,
from /opt/ros/kinetic/include/class_loader/multi_library_class_loader.h:35,
from /opt/ros/kinetic/include/pluginlib/./class_loader.hpp:38,
from /opt/ros/kinetic/include/pluginlib/class_loader.h:35,
from /opt/ros/kinetic/include/costmap_2d/costmap_2d_ros.h:49,
from /opt/ros/kinetic/include/nav_core/base_local_planner.h:42,
from /home/nvidia/planner_ws/src/rsband_local_planner/include/rsband_local_planner/rsband_local_planner_ros.h:47,
from /home/nvidia/planner_ws/src/rsband_local_planner/src/rsband_local_planner_ros.cpp:38:
/opt/ros/kinetic/include/class_loader/meta_object.hpp: In instantiation of ‘B* class_loader::class_loader_private::MetaObject<C, B>::create() const [with C = rsband_local_planner::RSBandPlannerROS; B = nav_core::BaseLocalPlanner]’:
/home/nvidia/planner_ws/src/rsband_local_planner/src/rsband_local_planner_ros.cpp:494:1: required from here
/opt/ros/kinetic/include/class_loader/meta_object.hpp:198:16: error: invalid new-expression of abstract class type ‘rsband_local_planner::RSBandPlannerROS’
return new C;
^
In file included from /home/nvidia/planner_ws/src/rsband_local_planner/src/rsband_local_planner_ros.cpp:38:0:
/home/nvidia/planner_ws/src/rsband_local_planner/include/rsband_local_planner/rsband_local_planner_ros.h:66:9: note: because the following virtual functions are pure within ‘rsband_local_planner::RSBandPlannerROS’:
class RSBandPlannerROS : public nav_core::BaseLocalPlanner
^
In file included from /home/nvidia/planner_ws/src/rsband_local_planner/include/rsband_local_planner/rsband_local_planner_ros.h:47:0,
from /home/nvidia/planner_ws/src/rsband_local_planner/src/rsband_local_planner_ros.cpp:38:
/opt/ros/kinetic/include/nav_core/base_local_planner.h:78:20: note: virtual void nav_core::BaseLocalPlanner::initialize(std::__cxx11::string, tf::TransformListener*, costmap_2d::Costmap2DROS*)
virtual void initialize(std::string name, tf::TransformListener* tf, cost
^
rsband_local_planner/CMakeFiles/rsband_local_planner.dir/build.make:62: recipe for target 'rsband_local_planner/CMakeFiles/rsband_local_planner.dir/src/rsband_local_planner_ros.cpp.o' failed
make[2]: *** [rsband_local_planner/CMakeFiles/rsband_local_planner.dir/src/rsband_local_planner_ros.cpp.o] Error 1
CMakeFiles/Makefile2:536: recipe for target 'rsband_local_planner/CMakeFiles/rsband_local_planner.dir/all' failed
make[1]: *** [rsband_local_planner/CMakeFiles/rsband_local_planner.dir/all] Error 2
Makefile:138: recipe for target 'all' failed
make: *** [all] Error 2
Invoking "make -j4 -l4" failed

Issue with reverse capabalities in RsBand planner

Case 1: emergency_planning: True and the path for the robot to go in the reverse direction
Dyaw value becomes greater than the set logic (dyaw > m_PI/2) for a path behind the robot and when emergency planning is set to true, keeps printing 'Reeds Shepp planning failed, attempting emergency planning' and also no command_vel output.

Case 2: emergency_planning: False and the path for the robot to go in the reverse direction
In fuzzy controller, the drcn variable fluctuates between -1 and 1 constantly due to ea's fluctuation. This causes the robot to oscillate forward and backward (+ve and -ve velocity commands).

Question about StartToEnd Strategy

Hi George,

First, great idea to combine eband planner and rs planner in a context of a local planner for Ackermann models. Amazing work !

Correct me if i'm wrong but the StartToEnd Strategy use the RS planner only for the start and end pose derived from the eband planner. However, knowing that the RS planner does not perform a path searching ( as global planner do ), how in this case he will find the best path between the two poses without a collision check between them ?

Maybe i missed something, and i'll really appreciate if you can clarify this point for me.

Thank you,

Compile errors with latest fuzzylite

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());

Setting plan to Elastic Band Failed

Now I am able to launch the rsband_local_planner.

But when I give a navigation goal by Rviz , I come across errors saying:

  • Setting plan to Elastic Band failed
  • Failed to pass global plan to the controller , aborting.

Will you point out a direction how to fix this?
Thank you very much!

Originally posted by @JWSLAM in #11 (comment)

error with catkin_make

Hey I wanted to try out your planer as an alternative to the teb_local.
I installed all the named dependencies and double checked that.
but when I try to catkin_make, I do now get the error, that there is a header.h missing:

In file included from /home/linus/catkin_ws/src/rsband_local_planner/src/fuzzy_ptc.cpp:38:0:
/home/linus/catkin_ws/src/rsband_local_planner/include/rsband_local_planner/fuzzy_ptc.h:52:10: fatal error: fl/Headers.h: File or directory not found
#include <fl/Headers.h>
^~~~~~~~~~~~~~
compilation terminated.

could deal with fuzzylite, but as I mentioned, I installed and also updated it.

Question about output

Hi,
I am trying to use your planner, but I can't really understand how to interpret what is published on /cmd_vel. I can see that linear.x, linear.y and angular.z are assigned values, but I'm not really sure what they mean. My vehicle is controlled by giving it linear speed and steering angle of the wheels. Obviously no problem with the meaning of linear.x, but not really sure how to interpret linear.y and angular.z. I noticed also that if I use the counter steering mode linear.y is always zero. Thanks for any help, I'm not sure if I should ask here or on the eband page, sorry in advance if it's the wrong place.

Failed to load library /home/xxx/catkin_ws/devel/lib//librsband_local_planner.so.

Hi gkouros,
When i add your plugin into the navigation package, I came across the problem as title.
I can find librsband_local_planner.so, but it seems that ROS try to find this .so in directory
/home/xxx/catkin_ws/devel/lib// instead of /home/xxx/catkin_ws/devel/lib/.
How can I fix it? Any suggestion will be highly appricieated!

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.