mesh_controller.h
Go to the documentation of this file.
1 /*
2  * Copyright 2020, Sebastian Pütz
3  *
4  * Redistribution and use in source and binary forms, with or without
5  * modification, are permitted provided that the following conditions
6  * are met:
7  *
8  * 1. Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  *
11  * 2. Redistributions in binary form must reproduce the above
12  * copyright notice, this list of conditions and the following
13  * disclaimer in the documentation and/or other materials provided
14  * with the distribution.
15  *
16  * 3. Neither the name of the copyright holder nor the names of its
17  * contributors may be used to endorse or promote products derived
18  * from this software without specific prior written permission.
19  *
20  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32  *
33  */
34 
35 #ifndef MESH_NAVIGATION__MESH_CONTROLLER_H
36 #define MESH_NAVIGATION__MESH_CONTROLLER_H
37 
39 #include <mbf_msgs/GetPathResult.h>
40 #include <mesh_controller/MeshControllerConfig.h>
41 #include <mesh_map/mesh_map.h>
42 #include <visualization_msgs/MarkerArray.h>
43 
44 namespace mesh_controller
45 {
47 {
48 public:
49 
52 
57 
61  virtual ~MeshController();
62 
72  virtual uint32_t computeVelocityCommands(const geometry_msgs::PoseStamped& pose,
73  const geometry_msgs::TwistStamped& velocity,
74  geometry_msgs::TwistStamped& cmd_vel, std::string& message);
75 
85  virtual bool isGoalReached(double dist_tolerance, double angle_tolerance);
86 
92  virtual bool setPlan(const std::vector<geometry_msgs::PoseStamped>& plan);
93 
98  virtual bool cancel();
99 
106  const geometry_msgs::PoseStamped& pose,
107  const tf2::Vector3& axis=tf2::Vector3(1,0,0));
108 
109 
116  const geometry_msgs::PoseStamped& pose);
117 
124  float gaussValue(const float& sigma_squared, const float& value);
125 
134  std::array<float, 2> naiveControl(
137  const mesh_map::Vector& mesh_dir,
138  const mesh_map::Normal& mesh_normal,
139  const float& mesh_cost);
140 
144  void reconfigureCallback(mesh_controller::MeshControllerConfig& cfg, uint32_t level);
145 
153  virtual bool initialize(const std::string& plugin_name, const boost::shared_ptr<tf2_ros::Buffer>& tf_ptr,
154  const boost::shared_ptr<mesh_map::MeshMap>& mesh_map_ptr);
155 
156 private:
157 
160 
162  vector<geometry_msgs::PoseStamped> current_plan;
163 
166 
169 
172 
175 
178 
180  dynamic_reconfigure::Server<mesh_controller::MeshControllerConfig>::CallbackType config_callback;
181 
183  MeshControllerConfig config;
184 
187 
189  std::atomic_bool cancel_requested;
190 };
191 
192 } /* namespace mesh_controller */
193 #endif /* MESH_NAVIGATION__MESH_CONTROLLER_H */
mesh_controller::MeshController::robot_dir
mesh_map::Normal robot_dir
Definition: mesh_controller.h:168
mesh_controller::MeshController::config
MeshControllerConfig config
current mesh controller configuration
Definition: mesh_controller.h:183
mesh_controller::MeshController::goal_dir
mesh_map::Normal goal_dir
the goal's and robot's orientation
Definition: mesh_controller.h:168
mesh_controller::MeshController::reconfigureCallback
void reconfigureCallback(mesh_controller::MeshControllerConfig &cfg, uint32_t level)
reconfigure callback function which is called if a dynamic reconfiguration were triggered.
Definition: mesh_controller.cpp:241
mesh_controller::MeshController::vector_map
lvr2::DenseVertexMap< mesh_map::Vector > vector_map
The vector field to the goal.
Definition: mesh_controller.h:174
ros::Publisher
lvr2::BaseVector
boost::shared_ptr
mesh_controller::MeshController::reconfigure_server_ptr
boost::shared_ptr< dynamic_reconfigure::Server< mesh_controller::MeshControllerConfig > > reconfigure_server_ptr
shared pointer to dynamic reconfigure server
Definition: mesh_controller.h:177
mesh_controller::MeshController::initialize
virtual bool initialize(const std::string &plugin_name, const boost::shared_ptr< tf2_ros::Buffer > &tf_ptr, const boost::shared_ptr< mesh_map::MeshMap > &mesh_map_ptr)
Initializes the controller plugin with a name, a tf pointer and a mesh map pointer.
Definition: mesh_controller.cpp:246
mesh_controller::MeshController::current_plan
vector< geometry_msgs::PoseStamped > current_plan
the current set plan
Definition: mesh_controller.h:162
mesh_controller::MeshController::MeshController
MeshController()
Constructor.
Definition: mesh_controller.cpp:61
mesh_controller::MeshController::naiveControl
std::array< float, 2 > naiveControl(const mesh_map::Vector &robot_pos, const mesh_map::Normal &robot_dir, const mesh_map::Vector &mesh_dir, const mesh_map::Normal &mesh_normal, const float &mesh_cost)
Definition: mesh_controller.cpp:222
mesh_controller::MeshController::config_callback
dynamic_reconfigure::Server< mesh_controller::MeshControllerConfig >::CallbackType config_callback
dynamic reconfigure callback function binding
Definition: mesh_controller.h:180
mesh_controller::MeshController::map_ptr
boost::shared_ptr< mesh_map::MeshMap > map_ptr
shared pointer to the used mesh map
Definition: mesh_controller.h:159
mesh_controller::MeshController::isGoalReached
virtual bool isGoalReached(double dist_tolerance, double angle_tolerance)
Checks if the robot reached to goal pose.
Definition: mesh_controller.cpp:174
lvr2::VectorMap
lvr2::Normal< float >
mesh_controller::MeshController::gaussValue
float gaussValue(const float &sigma_squared, const float &value)
Definition: mesh_controller.cpp:217
lvr2::OptionalFaceHandle
mesh_controller::MeshController::~MeshController
virtual ~MeshController()
Destructor.
Definition: mesh_controller.cpp:65
mesh_controller::MeshController::poseToPositionVector
mesh_map::Vector poseToPositionVector(const geometry_msgs::PoseStamped &pose)
Definition: mesh_controller.cpp:212
mesh_controller::MeshController::poseToDirectionVector
mesh_map::Normal poseToDirectionVector(const geometry_msgs::PoseStamped &pose, const tf2::Vector3 &axis=tf2::Vector3(1, 0, 0))
Definition: mesh_controller.cpp:204
mesh_controller::MeshController::goal_pos
mesh_map::Vector goal_pos
the goal and robot pose
Definition: mesh_controller.h:165
mesh_controller::MeshController::cancel_requested
std::atomic_bool cancel_requested
flag to handle cancel requests
Definition: mesh_controller.h:189
mesh_controller::MeshController::setPlan
virtual bool setPlan(const std::vector< geometry_msgs::PoseStamped > &plan)
Sets the current plan to follow, it also sets the vector field.
Definition: mesh_controller.cpp:181
mesh_controller::MeshController::current_face
lvr2::OptionalFaceHandle current_face
The triangle on which the robot is located.
Definition: mesh_controller.h:171
mesh_controller
Definition: mesh_controller.h:44
mesh_controller::MeshController::robot_pos
mesh_map::Vector robot_pos
Definition: mesh_controller.h:165
mesh_controller::MeshController::angle_pub
ros::Publisher angle_pub
publishes the angle between the robots orientation and the goal vector field for debug purposes
Definition: mesh_controller.h:186
mesh_controller.h
mesh_map.h
mbf_mesh_core::MeshController
mesh_controller::MeshController::cancel
virtual bool cancel()
Requests the planner to cancel, e.g. if it takes too much time.
Definition: mesh_controller.cpp:197
mesh_controller::MeshController::Ptr
boost::shared_ptr< mesh_controller::MeshController > Ptr
shared pointer typedef to simplify pointer access of the mesh controller
Definition: mesh_controller.h:51
mesh_controller::MeshController::computeVelocityCommands
virtual uint32_t computeVelocityCommands(const geometry_msgs::PoseStamped &pose, const geometry_msgs::TwistStamped &velocity, geometry_msgs::TwistStamped &cmd_vel, std::string &message)
Given the current position, orientation, and velocity of the robot, compute the next velocity command...
Definition: mesh_controller.cpp:69
mesh_controller::MeshController
Definition: mesh_controller.h:46


mesh_controller
Author(s): Sebastian Pütz , Sabrina Frohn
autogenerated on Thu Jan 25 2024 03:43:00