22 #ifndef __PLUGINS_VISPATHPLAN_VISPATHPLAN_THREAD_H_ 23 #define __PLUGINS_VISPATHPLAN_VISPATHPLAN_THREAD_H_ 25 #include <core/threading/thread.h> 26 #include <core/threading/mutex.h> 27 #include <core/utils/lockptr.h> 28 #include <aspect/configurable.h> 29 #include <aspect/logging.h> 30 #include <plugins/ros/aspect/ros.h> 31 #include <navgraph/navgraph.h> 32 #include <navgraph/navgraph_path.h> 34 #include <ros/publisher.h> 35 #include <visualization_msgs/MarkerArray.h> 63 void add_circle_markers(visualization_msgs::MarkerArray &m,
size_t &id_num,
64 float center_x,
float center_y,
float radius,
unsigned int arc_length,
65 float r,
float g,
float b,
float alpha,
float line_width = 0.03);
66 float edge_cost_factor(
67 std::list<std::tuple<std::string, std::string, std::string, float>> &costs,
68 const std::string &from,
const std::string &to, std::string &constraint_name);
72 size_t constraints_last_id_num_;
73 ros::Publisher vispub_;
75 float cfg_cost_scale_max_;
79 std::string plan_from_;
84 std::string cfg_global_frame_;
virtual void finalize()
Finalize the thread.
NavGraphVisualizationThread()
Constructor.
Thread aspect to get access to a ROS node handle.
void set_graph(fawkes::LockPtr< fawkes::NavGraph > &graph)
Set the graph.
void set_traversal(fawkes::NavGraphPath::Traversal &traversal)
Set current path.
virtual void graph_changed()
Function called if the graph has been changed.
Send Marker messages to rviz to show navgraph info.
Thread class encapsulation of pthreads.
void set_current_edge(std::string from, std::string to)
Set the currently executed edge of the plan.
Thread aspect to log output.
Sub-class representing a navgraph path traversal.
virtual void init()
Initialize the thread.
Thread aspect to access configuration data.
void set_constraint_repo(fawkes::LockPtr< fawkes::NavGraphConstraintRepo > &crepo)
Set the constraint repo.
void reset_plan()
Reset the current plan.
Topological graph change listener.
virtual void loop()
Code to execute in the thread.