jump_detector.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2018, the neonavigation authors
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #ifndef PLANNER_CSPACE_PLANNER_3D_JUMP_DETECTOR_H
31 #define PLANNER_CSPACE_PLANNER_3D_JUMP_DETECTOR_H
32 
33 #include <ros/ros.h>
34 
35 #include <tf2/utils.h>
38 
39 #include <string>
40 
42 {
43 protected:
48 
49  std::string jump_detect_frame_;
50  std::string map_frame_;
51 
52  double pos_jump_;
53  double yaw_jump_;
54 
55  bool init_;
56 
57 public:
58  explicit JumpDetector(tf2_ros::Buffer& tfbuf)
59  : tfbuf_(tfbuf)
60  , tfl_(tfbuf_)
61  , base_trans_prev_(tf2::Quaternion(0, 0, 0, 1))
62  , map_trans_prev_(tf2::Quaternion(0, 0, 0, 1))
63  , init_(false)
64  {
65  }
66  void setMapFrame(const std::string& frame_id)
67  {
68  map_frame_ = frame_id;
69  }
70  void setBaseFrame(const std::string& frame_id)
71  {
72  jump_detect_frame_ = frame_id;
73  }
74  void setThresholds(const double pos_jump, const double yaw_jump)
75  {
76  pos_jump_ = pos_jump;
77  yaw_jump_ = yaw_jump;
78  }
79  bool detectJump()
80  {
83  try
84  {
85  geometry_msgs::TransformStamped base_trans_tmp =
86  tfbuf_.lookupTransform(jump_detect_frame_, "base_link", ros::Time());
87  geometry_msgs::TransformStamped map_trans_tmp =
88  tfbuf_.lookupTransform(map_frame_, "base_link", ros::Time());
89  tf2::fromMsg(base_trans_tmp, base_trans);
90  tf2::fromMsg(map_trans_tmp, map_trans);
91  }
92  catch (tf2::TransformException& e)
93  {
94  return false;
95  }
96  const auto diff =
97  map_trans.inverse() * map_trans_prev_ * (base_trans_prev_.inverse() * base_trans);
98  base_trans_prev_ = base_trans;
99  map_trans_prev_ = map_trans;
100 
101  if (!init_)
102  {
103  init_ = true;
104  return false;
105  }
106 
107  const auto pos_diff = diff.getOrigin().length();
108  const auto yaw_diff = tf2::getYaw(diff.getRotation());
109 
110  if (pos_diff > pos_jump_ || fabs(yaw_diff) > yaw_jump_)
111  {
112  ROS_ERROR("Position jumped (%0.3f/%0.3f, %0.3f/%0.3f); clearing history",
113  pos_diff, pos_jump_, yaw_diff, yaw_jump_);
114  return true;
115  }
116  return false;
117  }
118 };
119 
120 #endif // PLANNER_CSPACE_PLANNER_3D_JUMP_DETECTOR_H
void setBaseFrame(const std::string &frame_id)
Definition: jump_detector.h:70
tf2_ros::TransformListener tfl_
Definition: jump_detector.h:45
tf2::Transform base_trans_prev_
Definition: jump_detector.h:46
tf2::Transform map_trans_prev_
Definition: jump_detector.h:47
std::string jump_detect_frame_
Definition: jump_detector.h:49
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
void setMapFrame(const std::string &frame_id)
Definition: jump_detector.h:66
std::string map_frame_
Definition: jump_detector.h:50
bool detectJump()
Definition: jump_detector.h:79
tf2_ros::Buffer & tfbuf_
Definition: jump_detector.h:44
JumpDetector(tf2_ros::Buffer &tfbuf)
Definition: jump_detector.h:58
void fromMsg(const A &, B &b)
Transform inverse() const
void setThresholds(const double pos_jump, const double yaw_jump)
Definition: jump_detector.h:74
double getYaw(const A &a)
double pos_jump_
Definition: jump_detector.h:52
double yaw_jump_
Definition: jump_detector.h:53
#define ROS_ERROR(...)


planner_cspace
Author(s): Atsushi Watanabe
autogenerated on Tue Jul 9 2019 05:00:13