collision_checker.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2018, Ubiquity Robotics
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  * 1. Redistributions of source code must retain the above copyright notice,
9  * this list of conditions and the following disclaimer.
10  * 2. Redistributions in binary form must reproduce the above copyright notice,
11  * this list of conditions and the following disclaimer in the documentation
12  * and/or other materials provided with the distribution.
13  *
14  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
15  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
16  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
17  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
18  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
19  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
20  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
21  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
22  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
23  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
24  * POSSIBILITY OF SUCH DAMAGE.
25  *
26  * The views and conclusions contained in the software and documentation are
27  * those of the authors and should not be interpreted as representing official
28  * policies, either expressed or implied, of the FreeBSD Project.
29  *
30  */
31 
32 #ifndef COLLISION_CHECKER_H
33 #define COLLISION_CHECKER_H
34 
36 #include <tf2_ros/buffer.h>
37 #include <sensor_msgs/Range.h>
38 #include <sensor_msgs/LaserScan.h>
39 
40 #include <mutex>
41 
43 
45 {
46  std::string baseFrame;
49  // footprint
50  float robot_width;
53 
58 
59  float max_age;
61  std::mutex obstacle_mutex;
62 
64 
65  void draw_line(const tf2::Vector3 &p1, const tf2::Vector3 &p2,
66  float r, float g, float b, int id);
67  void clear_line(int id);
68 
69  void check_dist(float x, bool forward, float& min_dist) const;
70  void check_angle(float theta, float x, float y,
71  bool left, float& min_dist) const;
72 
73  float degrees(float radians) const;
74 
75 public:
76  // Note that we take in refrences to tf_buffer and op, we expect these to outlive
77  // the useful life of this class, if they don't then you have a big issue.
78  //
79  // We don't store the NodeHandle, so that doesn't apply to it.
81 
82  // return distance in meters to closest obstacle
83  float obstacle_dist(bool forward, float &left_dist, float &right_dist,
84  tf2::Vector3 &fl, tf2::Vector3 &fr);
85 
86  // return distance in radians to closest obstacle
87  float obstacle_angle(bool left);
88 
89  float obstacle_arc_angle(double linear, double angular);
90 
91  double min_side_dist;
92  double max_side_dist;
93 };
94 
95 #endif
std::string baseFrame
void check_dist(float x, bool forward, float &min_dist) const
void check_angle(float theta, float x, float y, bool left, float &min_dist) const
float obstacle_arc_angle(double linear, double angular)
tf2_ros::Buffer & tf_buffer
ObstaclePoints & ob_points
float degrees(float radians) const
float obstacle_angle(bool left)
std::mutex obstacle_mutex
float obstacle_dist(bool forward, float &left_dist, float &right_dist, tf2::Vector3 &fl, tf2::Vector3 &fr)
void draw_line(const tf2::Vector3 &p1, const tf2::Vector3 &p2, float r, float g, float b, int id)
ros::Publisher line_pub
CollisionChecker(ros::NodeHandle &nh, tf2_ros::Buffer &tf_buffer, ObstaclePoints &op)


move_basic
Author(s): Jim Vaughan
autogenerated on Fri Mar 26 2021 02:46:58