single_thread_locomotor.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2017, Locus Robotics
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the copyright holder nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  */
00034 #include <locomotor/locomotor.h>
00035 #include <locomotor/locomotor_action_server.h>
00036 #include <nav_2d_utils/conversions.h>
00037 #include <string>
00038 
00039 namespace locomotor
00040 {
00041 using nav_core2::getResultCode;
00042 
00053 class SingleThreadLocomotor
00054 {
00055 public:
00056   explicit SingleThreadLocomotor(const ros::NodeHandle& private_nh)
00057     : private_nh_(private_nh), locomotor_(private_nh_), main_ex_(private_nh_, false),
00058       as_(private_nh_, std::bind(&SingleThreadLocomotor::setGoal, this, std::placeholders::_1))
00059   {
00060     private_nh_.param("controller_frequency", controller_frequency_, controller_frequency_);
00061     desired_control_duration_ = ros::Duration(1.0 / controller_frequency_);
00062     control_loop_timer_ = private_nh_.createTimer(desired_control_duration_,
00063                                                   &SingleThreadLocomotor::controlLoopCallback,
00064                                                   this, false, false);  // one_shot=false(default), auto_start=false
00065     locomotor_.initializeGlobalCostmap(main_ex_);
00066     locomotor_.initializeGlobalPlanners(main_ex_);
00067     locomotor_.initializeLocalCostmap(main_ex_);
00068     locomotor_.initializeLocalPlanners(main_ex_);
00069   }
00070 
00071   void setGoal(nav_2d_msgs::Pose2DStamped goal)
00072   {
00073     locomotor_.setGoal(goal);
00074     locomotor_.requestGlobalCostmapUpdate(main_ex_, main_ex_,
00075       std::bind(&SingleThreadLocomotor::onGlobalCostmapUpdate, this, std::placeholders::_1),
00076       std::bind(&SingleThreadLocomotor::onGlobalCostmapException, this, std::placeholders::_1, std::placeholders::_2));
00077   }
00078 
00079 protected:
00080   void requestGlobalCostmapUpdate()
00081   {
00082     locomotor_.requestGlobalCostmapUpdate(main_ex_, main_ex_,
00083       std::bind(&SingleThreadLocomotor::onGlobalCostmapUpdate, this, std::placeholders::_1),
00084       std::bind(&SingleThreadLocomotor::onGlobalCostmapException, this, std::placeholders::_1, std::placeholders::_2));
00085   }
00086 
00087   void requestNavigationFailure(const locomotor_msgs::ResultCode& result)
00088   {
00089     locomotor_.requestNavigationFailure(main_ex_, result,
00090       std::bind(&SingleThreadLocomotor::onNavigationFailure, this, std::placeholders::_1));
00091   }
00092 
00093   // Locomotor Callbacks
00094   void onGlobalCostmapUpdate(const ros::Duration& planning_time)
00095   {
00096     locomotor_.requestGlobalPlan(main_ex_, main_ex_,
00097       std::bind(&SingleThreadLocomotor::onNewGlobalPlan, this, std::placeholders::_1, std::placeholders::_2),
00098       std::bind(&SingleThreadLocomotor::onGlobalPlanningException, this, std::placeholders::_1, std::placeholders::_2));
00099   }
00100 
00101   void onGlobalCostmapException(nav_core2::NavCore2ExceptionPtr e_ptr, const ros::Duration& planning_time)
00102   {
00103     requestNavigationFailure(makeResultCode(locomotor_msgs::ResultCode::GLOBAL_COSTMAP, getResultCode(e_ptr),
00104                                             "Global Costmap failure."));
00105   }
00106 
00107   void onNewGlobalPlan(nav_2d_msgs::Path2D new_global_plan, const ros::Duration& planning_time)
00108   {
00109     locomotor_.publishPath(new_global_plan);
00110     locomotor_.getCurrentLocalPlanner().setPlan(new_global_plan);
00111     control_loop_timer_.start();
00112     as_.publishFeedback(locomotor_.getNavigationState());
00113   }
00114 
00115   void onGlobalPlanningException(nav_core2::NavCore2ExceptionPtr e_ptr, const ros::Duration& planning_time)
00116   {
00117     ROS_ERROR_NAMED("Locomotor", "Global planning error. Giving up.");
00118     requestNavigationFailure(makeResultCode(locomotor_msgs::ResultCode::GLOBAL_PLANNER, getResultCode(e_ptr),
00119                                             "Global Planning Failure."));
00120   }
00121 
00122   void controlLoopCallback(const ros::TimerEvent& event)
00123   {
00124     locomotor_.requestLocalCostmapUpdate(main_ex_, main_ex_,
00125       std::bind(&SingleThreadLocomotor::onLocalCostmapUpdate, this, std::placeholders::_1),
00126       std::bind(&SingleThreadLocomotor::onLocalCostmapException, this, std::placeholders::_1, std::placeholders::_2));
00127   }
00128 
00129   void onLocalCostmapUpdate(const ros::Duration& planning_time)
00130   {
00131     locomotor_.requestLocalPlan(main_ex_, main_ex_,
00132       std::bind(&SingleThreadLocomotor::onNewLocalPlan, this, std::placeholders::_1, std::placeholders::_2),
00133       std::bind(&SingleThreadLocomotor::onLocalPlanningException, this, std::placeholders::_1, std::placeholders::_2),
00134       std::bind(&SingleThreadLocomotor::onNavigationCompleted, this));
00135   }
00136 
00137   void onLocalCostmapException(nav_core2::NavCore2ExceptionPtr e_ptr, const ros::Duration& planning_time)
00138   {
00139     requestNavigationFailure(makeResultCode(locomotor_msgs::ResultCode::LOCAL_COSTMAP, getResultCode(e_ptr),
00140                                             "Local Costmap failure."));
00141   }
00142 
00143   void onNewLocalPlan(nav_2d_msgs::Twist2DStamped new_command, const ros::Duration& planning_time)
00144   {
00145     locomotor_.publishTwist(new_command);
00146     if (planning_time > desired_control_duration_)
00147     {
00148       ROS_WARN_NAMED("locomotor", "Control loop missed its desired rate of %.4fHz... "
00149                      "the loop actually took %.4f seconds (>%.4f).",
00150                      controller_frequency_, planning_time.toSec(), desired_control_duration_.toSec());
00151     }
00152     as_.publishFeedback(locomotor_.getNavigationState());
00153   }
00154 
00155   void onLocalPlanningException(nav_core2::NavCore2ExceptionPtr e_ptr, const ros::Duration& planning_time)
00156   {
00157     ROS_WARN_NAMED("Locomotor", "Local planning error. Creating new global plan.");
00158     control_loop_timer_.stop();
00159     requestGlobalCostmapUpdate();
00160   }
00161 
00162   void onNavigationCompleted()
00163   {
00164     ROS_INFO_NAMED("Locomotor", "Plan completed! Stopping.");
00165     control_loop_timer_.stop();
00166     as_.completeNavigation();
00167   }
00168 
00169   void onNavigationFailure(const locomotor_msgs::ResultCode result)
00170   {
00171     control_loop_timer_.stop();
00172     as_.failNavigation(result);
00173   }
00174 
00175   ros::NodeHandle private_nh_;
00176   // Locomotor Object
00177   Locomotor locomotor_;
00178 
00179   // Timer Stuff
00180   double controller_frequency_ { 20.0 };
00181   ros::Duration desired_control_duration_;
00182   ros::Timer control_loop_timer_;
00183 
00184   // Main Executor using Global CallbackQueue
00185   Executor main_ex_;
00186 
00187   // Action Server
00188   LocomotorActionServer as_;
00189 };
00190 };  // namespace locomotor
00191 
00192 int main(int argc, char** argv)
00193 {
00194   ros::init(argc, argv, "locomotor_node");
00195   ros::NodeHandle nh("~");
00196   locomotor::SingleThreadLocomotor sm(nh);
00197   ros::spin();
00198   return 0;
00199 }


locomotor
Author(s):
autogenerated on Wed Jun 26 2019 20:09:43