MultiRobotRouteToPathNode.cpp
Go to the documentation of this file.
1 /* Copyright (c) 2017, TU Wien
2  All rights reserved.
3 
4  Redistribution and use in source and binary forms, with or without
5  modification, are permitted provided that the following conditions are met:
6  * Redistributions of source code must retain the above copyright
7  notice, this list of conditions and the following disclaimer.
8  * Redistributions in binary form must reproduce the above copyright
9  notice, this list of conditions and the following disclaimer in the
10  documentation and/or other materials provided with the distribution.
11  * Neither the name of the <organization> nor the
12  names of its contributors may be used to endorse or promote products
13  derived from this software without specific prior written permission.
14 
15  THIS SOFTWARE IS PROVIDED BY TU Wien ''AS IS'' AND ANY
16  EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
17  WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
18  DISCLAIMED. IN NO EVENT SHALL TU Wien BE LIABLE FOR ANY
19  DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
20  (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
21  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
22  ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
23  (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
24  SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
25 */
26 #include <ros/ros.h>
28 #include <tf/transform_datatypes.h>
29 
30 int main(int argc, char **argv)
31 {
32 
33  ros::init(argc, argv, "route_to_path");
35 
37  ros::Rate r(20);
38 
39  while (ros::ok())
40  {
41  r.sleep();
42  ros::spinOnce();
43  }
44 
45  return 0;
46 }
47 
49 {
51  n_param_("~"),
52  robot_names_(std::vector<std::string>({"robot_0", "robot_1"}))
53 {
54  n_param_.param("robot_names", robot_names_, robot_names_);
55  std::string robot_names_string = "";
56  n_param_.param("robot_names_str", robot_names_string, robot_names_string);
57 
58  if (robot_names_string.size() > 0)
59  {
60  robot_names_string.erase(std::remove(robot_names_string.begin(), robot_names_string.end(), ' '), robot_names_string.end());
61  std::istringstream stringStr(robot_names_string);
62  std::string result;
63 
64  robot_names_.clear();
65 
66  while (std::getline(stringStr, result, ','))
67  {
68  robot_names_.push_back(result);
69  }
70  }
71 
72  no_robots_ = robot_names_.size();
73 
74  ROS_INFO("Subscribing %i robots", no_robots_);
75 
76  robot_steps_.resize(no_robots_);
77  pubPath_.resize(no_robots_);
78  subSegPath_.resize(no_robots_);
79  subOdometry_.resize(no_robots_);
80 
81  topic_path_ = "path_synced";
82  n_param_.param("path_topic", topic_path_, topic_path_);
83 
84  topic_seg_path_ = "seg_path";
85  n_param_.param("seg_path_topic", topic_seg_path_, topic_seg_path_);
86 
87  topic_odom_ = "odom";
88  n_param_.param("odom_topic", topic_odom_, topic_odom_);
89 
90  for (int i = 0; i < no_robots_; i++)
91  {
92  converter_.emplace_back(no_robots_, i);
93  observer_.emplace_back();
94  }
95 
96  for (int i = 0; i < no_robots_; i++)
97  {
98  pubPath_[i] = n.advertise<nav_msgs::Path>(robot_names_[i] + "/" + topic_path_, 100);
99 
100  subOdometry_[i] = n.subscribe<nav_msgs::Odometry>(robot_names_[i] + "/" + topic_odom_, 1, boost::bind(&MultiRobotRouteToPathNode::subOdomCb, this, _1, i));
101  subSegPath_[i] = n.subscribe<tuw_multi_robot_msgs::Route>(robot_names_[i] + "/" + topic_seg_path_, 1, boost::bind(&MultiRobotRouteToPathNode::subSegPathCb, this, _1, i));
102  }
103 }
104 
106 {
107  const nav_msgs::Odometry_<std::allocator<void>>::ConstPtr &odom = _event.getMessage();
108 
109  Eigen::Vector2d pt(odom->pose.pose.position.x, odom->pose.pose.position.y);
110 
111  bool changed = false;
112  robot_steps_[_topic] = observer_[_topic].getStep(pt, changed);
113 
114  if (changed)
115  {
116  for (int i = 0; i < no_robots_; i++)
117  {
118  std::vector<Eigen::Vector3d> newPath = converter_[i].updateSync(robot_steps_, changed);
119 
120  if (changed)
121  ROS_INFO("new path found %i %lu", i, newPath.size());
122 
123  if (changed)
124  publishPath(newPath, i);
125  }
126  }
127 }
128 
129 void MultiRobotRouteToPathNode::publishPath(std::vector<Eigen::Vector3d> _p, int _topic)
130 {
131  nav_msgs::Path path;
132  path.header.seq = 0;
133  path.header.stamp = ros::Time::now();
134  path.header.frame_id = "map";
135 
136  for (const Eigen::Vector3d &p : _p)
137  {
138  geometry_msgs::PoseStamped ps;
139  ps.header.seq = 0;
140  ps.header.stamp = ros::Time::now();
141  ps.header.frame_id = "map";
142 
143  ps.pose.position.x = p[0];
144  ps.pose.position.y = p[1];
145 
146  Eigen::Quaternion<float> q;
147  q = Eigen::AngleAxisf(p[2], Eigen::Vector3f::UnitZ());
148 
149  ps.pose.orientation.x = q.x();
150  ps.pose.orientation.y = q.y();
151  ps.pose.orientation.z = q.z();
152  ps.pose.orientation.w = q.w();
153  path.poses.push_back(ps);
154  }
155 
156  ROS_INFO("published path %i", _topic);
157  pubPath_[_topic].publish(path);
158 }
159 
161 {
162  for (uint32_t i = 0; i < robot_names_.size(); i++)
163  {
164  if (robot_names_[i].compare(_name) == 0)
165  return i;
166  }
167 
168  return -1;
169 }
170 
172 {
173  const tuw_multi_robot_msgs::Route_<std::allocator<void>>::ConstPtr &path = _event.getMessage();
174 
175  std::vector<SyncedPathPoint> localPath;
176  std::vector<PathSegment> segPath;
177 
178  if (path->segments.size() == 0)
179  return;
180 
181  for (const tuw_multi_robot_msgs::RouteSegment &seg : path->segments)
182  {
183  SyncedPathPoint spp;
184  PathSegment ps;
185 
186  ps.start[0] = seg.start.position.x;
187  ps.start[1] = seg.start.position.y;
188 
189  ps.goal[0] = seg.end.position.x;
190  ps.goal[1] = seg.end.position.y;
191 
192  ps.width = seg.width; //Its the radius :D
193 
194  double r, p, y;
195  tf::Quaternion q(seg.end.orientation.x, seg.end.orientation.y, seg.end.orientation.z, seg.end.orientation.w);
196  tf::Matrix3x3(q).getRPY(r, p, y);
197 
198  //float angle = atan2(seg.end.position.y - seg.start.position.y, seg.end.position.x - seg.start.position.x);
199 
200  spp.p[0] = seg.end.position.x;
201  spp.p[1] = seg.end.position.y;
202  spp.p[2] = y; //angle;
203 
204  for (const tuw_multi_robot_msgs::RoutePrecondition &pc : seg.preconditions)
205  {
206  PathPrecondition prec;
207  prec.robot_no = findRobotId(pc.robot_id);
208  prec.step = pc.current_route_segment;
209 
210  spp.sync.push_back(prec);
211  }
212 
213  segPath.push_back(ps);
214  localPath.push_back(spp);
215  }
216 
217  //Todo reset controllers with new Path
218  converter_[_topic].init(localPath);
219  observer_[_topic].init(segPath);
220  std::fill(robot_steps_.begin(), robot_steps_.end(), 0);
221 
222  bool chged = false;
223  std::vector<Eigen::Vector3d> newPath = converter_[_topic].updateSync(robot_steps_, chged);
224 
225  if (chged)
226  ROS_INFO("initial path found %i %lu", _topic, newPath.size());
227 
228  if (chged)
229  publishPath(newPath, _topic);
230 }
231 } // namespace tuw_multi_robot_route_to_path
void subSegPathCb(const ros::MessageEvent< tuw_multi_robot_msgs::Route const > &_event, int _topic)
void subOdomCb(const ros::MessageEvent< nav_msgs::Odometry const > &_event, int _topic)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void publishPath(std::vector< Eigen::Vector3d > _p, int _topic)
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
int main(int argc, char **argv)
ROSCPP_DECL bool ok()
bool sleep()
static Time now()
ROSCPP_DECL void spinOnce()
boost::shared_ptr< M > getMessage() const
ros::NodeHandle n_param_
Node handler to the current node.


tuw_multi_robot_route_to_path
Author(s): Benjamin Binder
autogenerated on Fri Jun 22 2018 03:07:12