segment_to_graph_node.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2017, <copyright holder> <email>
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  * * Redistributions of source code must retain the above copyright
8  * notice, this list of conditions and the following disclaimer.
9  * * Redistributions in binary form must reproduce the above copyright
10  * notice, this list of conditions and the following disclaimer in the
11  * documentation and/or other materials provided with the distribution.
12  * * Neither the name of the <organization> nor the
13  * names of its contributors may be used to endorse or promote products
14  * derived from this software without specific prior written permission.
15  *
16  * THIS SOFTWARE IS PROVIDED BY <copyright holder> <email> ''AS IS'' AND ANY
17  * EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18  * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19  * DISCLAIMED. IN NO EVENT SHALL <copyright holder> <email> BE LIABLE FOR ANY
20  * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21  * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23  * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24  * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25  * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26  *
27  */
28 
30 #include <nav_msgs/OccupancyGrid.h>
31 #include <tf/tf.h>
32 #include <boost/functional/hash.hpp>
33 #include "yaml-cpp/yaml.h"
34 
35 int main(int argc, char **argv)
36 {
37 
38  ros::init(argc, argv, "segment to graph");
40 
41  ros::Rate r(0.3);
42 
44 
45  while (ros::ok())
46  {
47  ros::spinOnce();
48  r.sleep();
49  node.Publish();
50  }
51 
52  return 0;
53 }
54 
55 namespace tuw_graph
56 {
58  n_param_("~")
59 {
60  segment_topic_ = "segments";
61  n_param_.param("segment_topic", segment_topic_, segment_topic_);
62 
63  segment_file_ = "segments.yaml";
64  n_param_.param("segment_file", segment_file_, segment_file_);
65 
66  path_length_ = 0.9; //meter
67  n_param_.param("segment_length", path_length_, path_length_);
68 
69  pubSegments_ = _n.advertise<tuw_multi_robot_msgs::Graph>(segment_topic_, 1);
70 
71  readSegments();
72 }
73 
75 {
77 }
78 
80 {
81  ROS_INFO("%s", segment_file_.c_str());
82  YAML::Node waypoints_yaml = YAML::LoadFile(segment_file_);
83  std::vector<double> start_x = (waypoints_yaml["start_x"].as<std::vector<double>>());
84  std::vector<double> start_y = (waypoints_yaml["start_y"].as<std::vector<double>>());
85  std::vector<double> end_x = (waypoints_yaml["end_x"].as<std::vector<double>>());
86  std::vector<double> end_y = (waypoints_yaml["end_y"].as<std::vector<double>>());
87  std::vector<double> path_space = (waypoints_yaml["space"].as<std::vector<double>>());
88  double origin_x = (waypoints_yaml["origin_x"].as<double>());
89  double origin_y = (waypoints_yaml["origin_y"].as<double>());
90  double resolution = (waypoints_yaml["resolution"].as<double>());
91 
92  std::vector<PathSeg> graph;
93 
94  for (uint32_t i = 0; i < start_x.size(); i++)
95  {
96  Eigen::Vector2d start((start_x[i] + origin_x) / resolution, (start_y[i] + origin_y) / resolution);
97  Eigen::Vector2d end((end_x[i] + origin_x) / resolution, (end_y[i] + origin_y) / resolution);
98  graph.emplace_back(start, end, path_space[i]);
99  }
100 
101  //TODO Precompute
102 
103  current_graph_.vertices.clear();
104  current_graph_.header.frame_id = "map";
105  current_graph_.header.seq = 0;
106  current_graph_.header.stamp = ros::Time::now();
107  current_graph_.origin.position.x = origin_x;
108  current_graph_.origin.position.y = origin_y;
109 
110  for (uint32_t i = 0; i < graph.size(); i++)
111  {
112  tuw_multi_robot_msgs::Vertex v;
113  v.id = i;
114 
115  v.weight = (graph[i].start - graph[i].end).norm();
116  v.width = graph[i].width / resolution;
117 
118  geometry_msgs::Point start;
119  start.x = graph[i].start[0];
120  start.y = graph[i].start[1];
121  start.z = 0;
122  geometry_msgs::Point end;
123  end.x = graph[i].end[0];
124  end.y = graph[i].end[1];
125  end.z = 0;
126 
127  v.path.push_back(start);
128  v.path.push_back(end);
129 
130  std::vector<int> pred = findNeighbors(graph, graph[i].start, i);
131 
132  for (int pr : pred)
133  {
134  v.predecessors.push_back(pr);
135  }
136 
137  std::vector<int> succ = findNeighbors(graph, graph[i].end, i);
138 
139  for (int sr : succ)
140  {
141  v.successors.push_back(sr);
142  }
143 
144  current_graph_.vertices.push_back(v);
145  }
146 
147  ROS_INFO("Segments parsed");
148 }
149 
150 std::vector<int32_t> SegmentToGraphNode::findNeighbors(std::vector<PathSeg> &_graph, Eigen::Vector2d _point, uint32_t _segment)
151 {
152  std::vector<int32_t> n;
153 
154  for (uint32_t i = 0; i < _graph.size(); i++)
155  {
156  if (i != _segment)
157  {
158  if ((_graph[i].start - _point).norm() < 0.1 || (_graph[i].end - _point).norm() < 0.1)
159  {
160  n.push_back(i);
161  }
162  }
163  }
164 
165  return n;
166 }
167 
168 } // namespace tuw_graph
ROSCPP_DECL void start()
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::vector< int32_t > findNeighbors(std::vector< PathSeg > &_graph, Eigen::Vector2d _point, uint32_t _segment)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
tuw_multi_robot_msgs::Graph current_graph_
#define ROS_INFO(...)
ROSCPP_DECL bool ok()
int main(int argc, char **argv)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool sleep()
ros::NodeHandle n_param_
Node handler to the current node.
static Time now()
ROSCPP_DECL void spinOnce()


tuw_voronoi_graph
Author(s): Benjamin Binder
autogenerated on Mon Feb 28 2022 23:57:47