Fawkes API
Fawkes Development Version
|
22 #ifndef _PLUGINS_VISPATHPLAN_VISPATHPLAN_THREAD_H_
23 #define _PLUGINS_VISPATHPLAN_VISPATHPLAN_THREAD_H_
25 #include "aspect/blocked_timing.h"
27 #include <aspect/configurable.h>
28 #include <aspect/logging.h>
29 #include <core/threading/mutex.h>
30 #include <core/threading/thread.h>
31 #include <core/utils/lockptr.h>
32 #include <navgraph/navgraph.h>
33 #include <navgraph/navgraph_path.h>
34 #include <plugins/ros/aspect/ros.h>
35 #include <ros/publisher.h>
36 #include <visualization_msgs/MarkerArray.h>
64 void add_circle_markers(visualization_msgs::MarkerArray &m,
69 unsigned int arc_length,
74 float line_width = 0.03);
75 float edge_cost_factor(std::list<std::tuple<std::string, std::string, std::string, float>> &costs,
76 const std::string & from,
77 const std::string & to,
78 std::string &constraint_name);
82 size_t constraints_last_id_num_;
83 ros::Publisher vispub_;
85 float cfg_cost_scale_max_;
89 std::string plan_from_;
94 std::string cfg_global_frame_;
96 visualization_msgs::MarkerArray markers_;
void reset_plan()
Reset the current plan.
Topological graph change listener.
virtual void loop()
Code to execute in the thread.
Thread aspect to use blocked timing.
virtual void init()
Initialize the thread.
void set_graph(fawkes::LockPtr< fawkes::NavGraph > &graph)
Set the graph.
Send Marker messages to rviz to show navgraph info.
virtual void graph_changed()
Function called if the graph has been changed.
Thread aspect to log output.
virtual void finalize()
Finalize the thread.
void set_current_edge(const std::string &from, const std::string &to)
Set the currently executed edge of the plan.
Thread aspect to get access to a ROS node handle.
void set_traversal(fawkes::NavGraphPath::Traversal &traversal)
Set current path.
Thread class encapsulation of pthreads.
Thread aspect to access configuration data.
Sub-class representing a navgraph path traversal.
NavGraphVisualizationThread()
Constructor.
void set_constraint_repo(fawkes::LockPtr< fawkes::NavGraphConstraintRepo > &crepo)
Set the constraint repo.