jump_detector.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2018, the neonavigation authors
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the copyright holder nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #ifndef PLANNER_CSPACE_PLANNER_3D_JUMP_DETECTOR_H
00031 #define PLANNER_CSPACE_PLANNER_3D_JUMP_DETECTOR_H
00032 
00033 #include <ros/ros.h>
00034 
00035 #include <tf2/utils.h>
00036 #include <tf2_geometry_msgs/tf2_geometry_msgs.h>
00037 #include <tf2_ros/transform_listener.h>
00038 
00039 #include <string>
00040 
00041 class JumpDetector
00042 {
00043 protected:
00044   tf2_ros::Buffer& tfbuf_;
00045   tf2_ros::TransformListener tfl_;
00046   tf2::Transform base_trans_prev_;
00047   tf2::Transform map_trans_prev_;
00048 
00049   std::string jump_detect_frame_;
00050   std::string map_frame_;
00051 
00052   double pos_jump_;
00053   double yaw_jump_;
00054 
00055   bool init_;
00056 
00057 public:
00058   explicit JumpDetector(tf2_ros::Buffer& tfbuf)
00059     : tfbuf_(tfbuf)
00060     , tfl_(tfbuf_)
00061     , base_trans_prev_(tf2::Quaternion(0, 0, 0, 1))
00062     , map_trans_prev_(tf2::Quaternion(0, 0, 0, 1))
00063     , init_(false)
00064   {
00065   }
00066   void setMapFrame(const std::string& frame_id)
00067   {
00068     map_frame_ = frame_id;
00069   }
00070   void setBaseFrame(const std::string& frame_id)
00071   {
00072     jump_detect_frame_ = frame_id;
00073   }
00074   void setThresholds(const double pos_jump, const double yaw_jump)
00075   {
00076     pos_jump_ = pos_jump;
00077     yaw_jump_ = yaw_jump;
00078   }
00079   bool detectJump()
00080   {
00081     tf2::Stamped<tf2::Transform> base_trans;
00082     tf2::Stamped<tf2::Transform> map_trans;
00083     try
00084     {
00085       geometry_msgs::TransformStamped base_trans_tmp =
00086           tfbuf_.lookupTransform(jump_detect_frame_, "base_link", ros::Time());
00087       geometry_msgs::TransformStamped map_trans_tmp =
00088           tfbuf_.lookupTransform(map_frame_, "base_link", ros::Time());
00089       tf2::fromMsg(base_trans_tmp, base_trans);
00090       tf2::fromMsg(map_trans_tmp, map_trans);
00091     }
00092     catch (tf2::TransformException& e)
00093     {
00094       return false;
00095     }
00096     const auto diff =
00097         map_trans.inverse() * map_trans_prev_ * (base_trans_prev_.inverse() * base_trans);
00098     base_trans_prev_ = base_trans;
00099     map_trans_prev_ = map_trans;
00100 
00101     if (!init_)
00102     {
00103       init_ = true;
00104       return false;
00105     }
00106 
00107     const auto pos_diff = diff.getOrigin().length();
00108     const auto yaw_diff = tf2::getYaw(diff.getRotation());
00109 
00110     if (pos_diff > pos_jump_ || fabs(yaw_diff) > yaw_jump_)
00111     {
00112       ROS_ERROR("Position jumped (%0.3f/%0.3f, %0.3f/%0.3f); clearing history",
00113                 pos_diff, pos_jump_, yaw_diff, yaw_jump_);
00114       return true;
00115     }
00116     return false;
00117   }
00118 };
00119 
00120 #endif  // PLANNER_CSPACE_PLANNER_3D_JUMP_DETECTOR_H


planner_cspace
Author(s): Atsushi Watanabe
autogenerated on Sat Jun 22 2019 20:07:27