22 #ifndef _PLUGINS_VISPATHPLAN_VISPATHPLAN_THREAD_H_ 23 #define _PLUGINS_VISPATHPLAN_VISPATHPLAN_THREAD_H_ 25 #include <aspect/configurable.h> 26 #include <aspect/logging.h> 27 #include <core/threading/mutex.h> 28 #include <core/threading/thread.h> 29 #include <core/utils/lockptr.h> 30 #include <navgraph/navgraph.h> 31 #include <navgraph/navgraph_path.h> 32 #include <plugins/ros/aspect/ros.h> 33 #include <ros/publisher.h> 34 #include <visualization_msgs/MarkerArray.h> 60 void add_circle_markers(visualization_msgs::MarkerArray &m,
65 unsigned int arc_length,
70 float line_width = 0.03);
71 float edge_cost_factor(std::list<std::tuple<std::string, std::string, std::string, float>> &costs,
72 const std::string & from,
73 const std::string & to,
74 std::string &constraint_name);
78 size_t constraints_last_id_num_;
79 ros::Publisher vispub_;
81 float cfg_cost_scale_max_;
85 std::string plan_from_;
90 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_current_edge(const std::string &from, const std::string &to)
Set the currently executed edge of the plan.
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.
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.