Fawkes API  Fawkes Development Version
visualization_thread.h
1 
2 /***************************************************************************
3  * visualization_thread.h - Visualization for pathplan via rviz
4  *
5  * Created: Fri Nov 11 21:17:24 2011
6  * Copyright 2011-2012 Tim Niemueller [www.niemueller.de]
7  ****************************************************************************/
8 
9 /* This program is free software; you can redistribute it and/or modify
10  * it under the terms of the GNU General Public License as published by
11  * the Free Software Foundation; either version 2 of the License, or
12  * (at your option) any later version.
13  *
14  * This program is distributed in the hope that it will be useful,
15  * but WITHOUT ANY WARRANTY; without even the implied warranty of
16  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
17  * GNU Library General Public License for more details.
18  *
19  * Read the full text in the LICENSE.GPL file in the doc directory.
20  */
21 
22 #ifndef _PLUGINS_VISPATHPLAN_VISPATHPLAN_THREAD_H_
23 #define _PLUGINS_VISPATHPLAN_VISPATHPLAN_THREAD_H_
24 
25 #include "aspect/blocked_timing.h"
26 
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>
37 
41  public fawkes::LoggingAspect,
42  public fawkes::ROSAspect,
44 {
45 public:
47 
48  virtual void init();
49  virtual void loop();
50  virtual void finalize();
51 
54 
56  void set_current_edge(const std::string &from, const std::string &to);
57  void reset_plan();
58 
59  virtual void graph_changed() throw();
60 
61 private:
62  void publish();
63  void regenerate();
64  void add_circle_markers(visualization_msgs::MarkerArray &m,
65  size_t & id_num,
66  float center_x,
67  float center_y,
68  float radius,
69  unsigned int arc_length,
70  float r,
71  float g,
72  float b,
73  float alpha,
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);
79 
80 private:
81  size_t last_id_num_;
82  size_t constraints_last_id_num_;
83  ros::Publisher vispub_;
84 
85  float cfg_cost_scale_max_;
86 
88  std::string plan_to_;
89  std::string plan_from_;
90 
93 
94  std::string cfg_global_frame_;
95 
96  visualization_msgs::MarkerArray markers_;
97 };
98 
99 #endif
Send Marker messages to rviz to show navgraph info.
void set_constraint_repo(fawkes::LockPtr< fawkes::NavGraphConstraintRepo > &crepo)
Set the constraint repo.
virtual void graph_changed()
Function called if the graph has been changed.
virtual void loop()
Code to execute in the thread.
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.
void set_graph(fawkes::LockPtr< fawkes::NavGraph > &graph)
Set the graph.
virtual void init()
Initialize the thread.
void set_traversal(fawkes::NavGraphPath::Traversal &traversal)
Set current path.
void reset_plan()
Reset the current plan.
Thread aspect to use blocked timing.
Thread aspect to access configuration data.
Definition: configurable.h:33
Thread aspect to log output.
Definition: logging.h:33
Sub-class representing a navgraph path traversal.
Definition: navgraph_path.h:40
Topological graph change listener.
Definition: navgraph.h:179
Thread aspect to get access to a ROS node handle.
Definition: ros.h:39
Thread class encapsulation of pthreads.
Definition: thread.h:46