exceptions.h
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 #ifndef NAV_CORE2_EXCEPTIONS_H
00035 #define NAV_CORE2_EXCEPTIONS_H
00036 
00037 #include <nav_2d_msgs/Pose2DStamped.h>
00038 #include <stdexcept>
00039 #include <exception>
00040 #include <string>
00041 #include <memory>
00042 
00043 /**************************************************
00044  * The nav_core2 Planning Exception Hierarchy!!
00045  * (with arbitrary integer result codes)
00046  **************************************************
00047  *   NavCore2Exception
00048  * 0   CostmapException
00049  * 1     CostmapSafetyException
00050  * 2       CostmapDataLagException
00051  * 3   PlannerException
00052  * 4     GlobalPlannerException
00053  * 5       InvalidStartPoseException
00054  * 6         StartBoundsException
00055  * 7         OccupiedStartException
00056  * 8       InvalidGoalPoseException
00057  * 9         GoalBoundsException
00058  * 10        OccupiedGoalException
00059  * 11      NoGlobalPathException
00060  * 12      GlobalPlannerTimeoutException
00061  * 13    LocalPlannerException
00062  * 14      IllegalTrajectoryException
00063  * 15      NoLegalTrajectoriesException
00064  * 16    PlannerTFException
00065  *
00066  * -1 Unknown
00067  **************************************************/
00068 
00069 namespace nav_core2
00070 {
00071 
00072 inline std::string poseToString(const nav_2d_msgs::Pose2DStamped& pose)
00073 {
00074   return "(" + std::to_string(pose.pose.x) + ", " + std::to_string(pose.pose.y) + ", " + std::to_string(pose.pose.theta)
00075          + " : " + pose.header.frame_id + ")";
00076 }
00077 
00078 class NavCore2Exception: public std::runtime_error
00079 {
00080 public:
00081   explicit NavCore2Exception(const std::string& description, int result_code)
00082     : std::runtime_error(description), result_code_(result_code) {}
00083   int getResultCode() const { return result_code_; }
00084 protected:
00085   int result_code_;
00086 };
00087 
00088 using NavCore2ExceptionPtr = std::exception_ptr;
00089 
00093 inline int getResultCode(const NavCore2ExceptionPtr& e_ptr)
00094 {
00095   if (e_ptr == nullptr)
00096   {
00097     return -1;
00098   }
00099   try
00100   {
00101     std::rethrow_exception(e_ptr);
00102   }
00103   catch (const NavCore2Exception& e)
00104   {
00105     return e.getResultCode();
00106   }
00107   catch (...)
00108   {
00109     // Will end up here if current_exception returned a non-NavCore2Exception
00110     return -1;
00111   }
00112 }
00113 
00118 class CostmapException: public NavCore2Exception
00119 {
00120 public:
00121   explicit CostmapException(const std::string& description, int result_code = 0)
00122     : NavCore2Exception(description, result_code) {}
00123 };
00124 
00129 class CostmapSafetyException: public CostmapException
00130 {
00131 public:
00132   explicit CostmapSafetyException(const std::string& description, int result_code = 1)
00133     : CostmapException(description, result_code) {}
00134 };
00135 
00142 class CostmapDataLagException: public CostmapSafetyException
00143 {
00144 public:
00145   explicit CostmapDataLagException(const std::string& description, int result_code = 2)
00146     : CostmapSafetyException(description, result_code) {}
00147 };
00148 
00153 class PlannerException: public NavCore2Exception
00154 {
00155 public:
00156   explicit PlannerException(const std::string& description, int result_code = 3)
00157     : NavCore2Exception(description, result_code) {}
00158 };
00159 
00164 class GlobalPlannerException: public PlannerException
00165 {
00166 public:
00167   explicit GlobalPlannerException(const std::string& description, int result_code = 4)
00168     : PlannerException(description, result_code) {}
00169 };
00170 
00175 class LocalPlannerException: public PlannerException
00176 {
00177 public:
00178   explicit LocalPlannerException(const std::string& description, int result_code = 13)
00179     : PlannerException(description, result_code) {}
00180 };
00181 
00186 class PlannerTFException: public PlannerException
00187 {
00188 public:
00189   explicit PlannerTFException(const std::string& description, int result_code = 16)
00190     : PlannerException(description, result_code) {}
00191 };
00192 
00197 class InvalidStartPoseException: public GlobalPlannerException
00198 {
00199 public:
00200   explicit InvalidStartPoseException(const std::string& description, int result_code = 5)
00201     : GlobalPlannerException(description, result_code) {}
00202   InvalidStartPoseException(const nav_2d_msgs::Pose2DStamped& pose, const std::string& problem, int result_code = 5) :
00203     InvalidStartPoseException("The starting pose " + poseToString(pose) + " is " + problem, result_code) {}
00204 };
00205 
00210 class StartBoundsException: public InvalidStartPoseException
00211 {
00212 public:
00213   explicit StartBoundsException(const std::string& description, int result_code = 6)
00214     : InvalidStartPoseException(description, result_code) {}
00215   explicit StartBoundsException(const nav_2d_msgs::Pose2DStamped& pose) :
00216     InvalidStartPoseException(pose, "out of bounds", 6) {}
00217 };
00218 
00223 class OccupiedStartException: public InvalidStartPoseException
00224 {
00225 public:
00226   explicit OccupiedStartException(const std::string& description, int result_code = 7)
00227     : InvalidStartPoseException(description, result_code) {}
00228   explicit OccupiedStartException(const nav_2d_msgs::Pose2DStamped& pose) :
00229     InvalidStartPoseException(pose, "occupied", 7) {}
00230 };
00231 
00236 class InvalidGoalPoseException: public GlobalPlannerException
00237 {
00238 public:
00239   explicit InvalidGoalPoseException(const std::string& description, int result_code = 8)
00240     : GlobalPlannerException(description, result_code) {}
00241   InvalidGoalPoseException(const nav_2d_msgs::Pose2DStamped& pose, const std::string& problem, int result_code = 8) :
00242     GlobalPlannerException("The goal pose " + poseToString(pose) + " is " + problem, result_code) {}
00243 };
00244 
00249 class GoalBoundsException: public InvalidGoalPoseException
00250 {
00251 public:
00252   explicit GoalBoundsException(const std::string& description, int result_code = 9)
00253     : InvalidGoalPoseException(description, result_code) {}
00254   explicit GoalBoundsException(const nav_2d_msgs::Pose2DStamped& pose) :
00255     InvalidGoalPoseException(pose, "out of bounds", 9) {}
00256 };
00257 
00262 class OccupiedGoalException: public InvalidGoalPoseException
00263 {
00264 public:
00265   explicit OccupiedGoalException(const std::string& description, int result_code = 10)
00266     : InvalidGoalPoseException(description, result_code) {}
00267   explicit OccupiedGoalException(const nav_2d_msgs::Pose2DStamped& pose) :
00268     InvalidGoalPoseException(pose, "occupied", 10) {}
00269 };
00270 
00275 class NoGlobalPathException: public GlobalPlannerException
00276 {
00277 public:
00278   explicit NoGlobalPathException(const std::string& description, int result_code = 11)
00279     : GlobalPlannerException(description, result_code) {}
00280   NoGlobalPathException() : GlobalPlannerException("No global path found.") {}
00281 };
00282 
00287 class GlobalPlannerTimeoutException: public GlobalPlannerException
00288 {
00289 public:
00290   explicit GlobalPlannerTimeoutException(const std::string& description, int result_code = 12)
00291     : GlobalPlannerException(description, result_code) {}
00292 };
00293 
00298 class IllegalTrajectoryException: public LocalPlannerException
00299 {
00300 public:
00301   IllegalTrajectoryException(const std::string& critic_name, const std::string& description, int result_code = 14)
00302     : LocalPlannerException(description, result_code), critic_name_(critic_name) {}
00303   std::string getCriticName() const { return critic_name_; }
00304 protected:
00305   std::string critic_name_;
00306 };
00307 
00312 class NoLegalTrajectoriesException: public LocalPlannerException
00313 {
00314 public:
00315   explicit NoLegalTrajectoriesException(const std::string& description, int result_code = 15)
00316     : LocalPlannerException(description, result_code) {}
00317 };
00318 
00319 }  // namespace nav_core2
00320 
00321 #endif  // NAV_CORE2_EXCEPTIONS_H


nav_core2
Author(s):
autogenerated on Wed Jun 26 2019 20:09:31