Go to the documentation of this file.
35 #ifndef MESH_NAVIGATION__MESH_CONTROLLER_H
36 #define MESH_NAVIGATION__MESH_CONTROLLER_H
39 #include <mbf_msgs/GetPathResult.h>
40 #include <mesh_controller/MeshControllerConfig.h>
42 #include <visualization_msgs/MarkerArray.h>
73 const geometry_msgs::TwistStamped& velocity,
74 geometry_msgs::TwistStamped& cmd_vel, std::string& message);
85 virtual bool isGoalReached(
double dist_tolerance,
double angle_tolerance);
92 virtual bool setPlan(
const std::vector<geometry_msgs::PoseStamped>& plan);
106 const geometry_msgs::PoseStamped& pose,
107 const tf2::Vector3& axis=tf2::Vector3(1,0,0));
116 const geometry_msgs::PoseStamped& pose);
124 float gaussValue(
const float& sigma_squared,
const float& value);
139 const float& mesh_cost);
180 dynamic_reconfigure::Server<mesh_controller::MeshControllerConfig>::CallbackType
config_callback;
mesh_map::Normal robot_dir
MeshControllerConfig config
current mesh controller configuration
mesh_map::Normal goal_dir
the goal's and robot's orientation
void reconfigureCallback(mesh_controller::MeshControllerConfig &cfg, uint32_t level)
reconfigure callback function which is called if a dynamic reconfiguration were triggered.
lvr2::DenseVertexMap< mesh_map::Vector > vector_map
The vector field to the goal.
boost::shared_ptr< dynamic_reconfigure::Server< mesh_controller::MeshControllerConfig > > reconfigure_server_ptr
shared pointer to dynamic reconfigure server
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.
vector< geometry_msgs::PoseStamped > current_plan
the current set plan
MeshController()
Constructor.
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)
dynamic_reconfigure::Server< mesh_controller::MeshControllerConfig >::CallbackType config_callback
dynamic reconfigure callback function binding
boost::shared_ptr< mesh_map::MeshMap > map_ptr
shared pointer to the used mesh map
virtual bool isGoalReached(double dist_tolerance, double angle_tolerance)
Checks if the robot reached to goal pose.
float gaussValue(const float &sigma_squared, const float &value)
virtual ~MeshController()
Destructor.
mesh_map::Vector poseToPositionVector(const geometry_msgs::PoseStamped &pose)
mesh_map::Normal poseToDirectionVector(const geometry_msgs::PoseStamped &pose, const tf2::Vector3 &axis=tf2::Vector3(1, 0, 0))
mesh_map::Vector goal_pos
the goal and robot pose
std::atomic_bool cancel_requested
flag to handle cancel requests
virtual bool setPlan(const std::vector< geometry_msgs::PoseStamped > &plan)
Sets the current plan to follow, it also sets the vector field.
lvr2::OptionalFaceHandle current_face
The triangle on which the robot is located.
mesh_map::Vector robot_pos
ros::Publisher angle_pub
publishes the angle between the robots orientation and the goal vector field for debug purposes
virtual bool cancel()
Requests the planner to cancel, e.g. if it takes too much time.
boost::shared_ptr< mesh_controller::MeshController > Ptr
shared pointer typedef to simplify pointer access of the mesh controller
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...
mesh_controller
Author(s): Sebastian Pütz
, Sabrina Frohn
autogenerated on Thu Jan 25 2024 03:43:00