MultiRobotLocalBehaviorController.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 #include <tuw_multi_robot_msgs/RobotInfo.h>
30 
31 int main(int argc, char **argv)
32 {
33 
34  ros::init(argc, argv, "route_to_path");
36 
38  ros::Rate r(20);
39 
40  while (ros::ok())
41  {
42  r.sleep();
43  ros::spinOnce();
44  ctrl.publishRobotInfo();
45  }
46 
47  return 0;
48 }
49 
51 {
53  n_param_("~"),
54  robot_names_(std::vector<std::string>({"robot_0", "robot_1"}))
55 {
56  n_param_.param("robot_names", robot_names_, robot_names_);
57  std::string robot_names_string = "";
58  n_param_.param("robot_names_str", robot_names_string, robot_names_string);
59 
60  if (robot_names_string.size() > 0)
61  {
62  robot_names_string.erase(std::remove(robot_names_string.begin(), robot_names_string.end(), ' '), robot_names_string.end());
63  std::istringstream stringStr(robot_names_string);
64  std::string result;
65 
66  robot_names_.clear();
67 
68  while (std::getline(stringStr, result, ','))
69  {
70  robot_names_.push_back(result);
71  }
72  }
73 
74  for(int i = 0; i < robot_names_.size(); i++)
75  {
76  std::cout << "robot_name[" << i << "] = " << robot_names_[i] << std::endl;
77  }
78 
79  n_param_.param("robot_radius", robot_radius_, robot_radius_);
80  robotDefaultRadius_ = 0.3;
81  n_param_.param("robot_default_radius", robotDefaultRadius_, robotDefaultRadius_);
82 
83  no_robots_ = robot_names_.size();
84 
85  ROS_INFO("Subscribing %i robots", no_robots_);
86 
87  robot_steps_.resize(no_robots_);
88  pubPath_.resize(no_robots_);
89  subSegPath_.resize(no_robots_);
90  subOdometry_.resize(no_robots_);
92  robot_pose_.resize(no_robots_);
93 
94  n_param_.param<std::string>("path_topic", topic_path_, "path_synced");
95 
96  n_param_.param<std::string>("route_topic", topic_route_, "route");
97 
98  n_param_.param<std::string>("odom_topic", topic_odom_, "odom");
99 
100  n_param_.param<std::string>("robotInfo_topic", topic_robot_info_, "/robot_info");
101 
102  n_param_.param<std::string>("frame_map", frame_map_, "map");
103 
104  for (int i = 0; i < no_robots_; i++)
105  {
106  converter_.emplace_back(no_robots_, i);
107  observer_.emplace_back();
108  }
109 
110  for (int i = 0; i < no_robots_; i++)
111  {
112  pubPath_[i] = n.advertise<nav_msgs::Path>(robot_names_[i] + "/" + topic_path_, 100);
113 
114  subOdometry_[i] = n.subscribe<nav_msgs::Odometry>(robot_names_[i] + "/" + topic_odom_, 1, boost::bind(&MultiRobotLocalBehaviorController::subOdomCb, this, _1, i));
115  subSegPath_[i] = n.subscribe<tuw_multi_robot_msgs::Route>(robot_names_[i] + "/" + topic_route_, 1, boost::bind(&MultiRobotLocalBehaviorController::subSegPathCb, this, _1, i));
116  }
117 
118  pubRobotInfo_ = n.advertise<tuw_multi_robot_msgs::RobotInfo>(topic_robot_info_, 10);
119 }
120 
122 {
123  const nav_msgs::Odometry_<std::allocator<void>>::ConstPtr &odom = _event.getMessage();
124  robot_pose_[_topic] = odom->pose;
125  Eigen::Vector2d pt(odom->pose.pose.position.x, odom->pose.pose.position.y);
126 
127  bool changed = false;
128  robot_steps_[_topic] = observer_[_topic].getStep(pt, changed);
129 
130  if (changed)
131  {
132  for (int i = 0; i < no_robots_; i++)
133  {
134  std::vector<Eigen::Vector3d> newPath = converter_[i].updateSync(robot_steps_, changed);
135 
136  if (changed)
137  ROS_INFO("new path found %i %lu", i, newPath.size());
138 
139  if (changed)
140  publishPath(newPath, i);
141  }
142  }
143 }
144 
145 void MultiRobotLocalBehaviorController::publishPath(std::vector<Eigen::Vector3d> _p, int _topic)
146 {
147  nav_msgs::Path path;
148  path.header.seq = 0;
149  path.header.stamp = ros::Time::now();
150  path.header.frame_id = frame_map_;
151 
152  for (const Eigen::Vector3d &p : _p)
153  {
154  geometry_msgs::PoseStamped ps;
155  ps.header.seq = 0;
156  ps.header.stamp = ros::Time::now();
157  ps.header.frame_id = frame_map_;
158 
159  ps.pose.position.x = p[0];
160  ps.pose.position.y = p[1];
161 
162  Eigen::Quaternion<float> q;
163  q = Eigen::AngleAxisf(p[2], Eigen::Vector3f::UnitZ());
164 
165  ps.pose.orientation.x = q.x();
166  ps.pose.orientation.y = q.y();
167  ps.pose.orientation.z = q.z();
168  ps.pose.orientation.w = q.w();
169  path.poses.push_back(ps);
170  }
171 
172  ROS_INFO("published path %i", _topic);
173  pubPath_[_topic].publish(path);
174 }
175 
177 {
178  for (uint32_t i = 0; i < robot_names_.size(); i++)
179  {
180  if (robot_names_[i].compare(_name) == 0)
181  return i;
182  }
183 
184  return -1;
185 }
186 
188 {
189  const tuw_multi_robot_msgs::Route_<std::allocator<void>>::ConstPtr &path = _event.getMessage();
190 
191  std::vector<SyncedPathPoint> localPath;
192  std::vector<PathSegment> segPath;
193 
194  if (path->segments.size() == 0)
195  return;
196 
197  for (const tuw_multi_robot_msgs::RouteSegment &seg : path->segments)
198  {
199  SyncedPathPoint spp;
200  PathSegment ps;
201 
202  ps.start[0] = seg.start.position.x;
203  ps.start[1] = seg.start.position.y;
204 
205  ps.goal[0] = seg.end.position.x;
206  ps.goal[1] = seg.end.position.y;
207 
208  ps.width = seg.width; //Its the radius :D
209 
210  double r, p, y;
211  tf::Quaternion q(seg.end.orientation.x, seg.end.orientation.y, seg.end.orientation.z, seg.end.orientation.w);
212  tf::Matrix3x3(q).getRPY(r, p, y);
213 
214  //float angle = atan2(seg.end.position.y - seg.start.position.y, seg.end.position.x - seg.start.position.x);
215 
216  spp.p[0] = seg.end.position.x;
217  spp.p[1] = seg.end.position.y;
218  spp.p[2] = y; //angle;
219 
220  for (const tuw_multi_robot_msgs::RoutePrecondition &pc : seg.preconditions)
221  {
222  PathPrecondition prec;
223  prec.robot_no = findRobotId(pc.robot_id);
224  prec.step = pc.current_route_segment;
225 
226  spp.sync.push_back(prec);
227  }
228 
229  segPath.push_back(ps);
230  localPath.push_back(spp);
231  }
232 
233  //Todo reset controllers with new Path
234  converter_[_topic].init(localPath);
235  observer_[_topic].init(segPath);
236  std::fill(robot_steps_.begin(), robot_steps_.end(), 0);
237 
238  bool chged = false;
239  std::vector<Eigen::Vector3d> newPath = converter_[_topic].updateSync(robot_steps_, chged);
240 
241  if (chged)
242  ROS_INFO("initial path found %i %lu", _topic, newPath.size());
243 
244  if (chged)
245  publishPath(newPath, _topic);
246 }
247 
249 {
250  for (uint32_t i = 0; i < robot_names_.size(); i++)
251  {
252  tuw_multi_robot_msgs::RobotInfo ri;
253  ri.header.stamp = ros::Time::now();
254  ri.header.frame_id = frame_map_;
255  ri.robot_name = robot_names_[i];
256  ri.pose = robot_pose_[i];
257  ri.shape = ri.SHAPE_CIRCLE;
258  ri.shape_variables.push_back(robot_radius_[i]);
259  ri.sync.robot_id = robot_names_[i];
260  ri.sync.current_route_segment = robot_steps_[i];
261  ri.mode = ri.MODE_NA;
262  ri.status = ri.STATUS_STOPPED; //TODO
263  ri.good_id = ri.GOOD_NA;
264 
266  }
267 }
268 } // namespace tuw_multi_robot_route_to_path
tuw_multi_robot_route_to_path::MultiRobotLocalBehaviorController::robot_names_
std::vector< std::string > robot_names_
Definition: MultiRobotLocalBehaviorController.h:68
tuw_multi_robot_route_to_path::MultiRobotLocalBehaviorController::n_param_
ros::NodeHandle n_param_
Node handler to the current node.
Definition: MultiRobotLocalBehaviorController.h:50
tuw_multi_robot_route_to_path::SyncedPathPoint
Definition: RobotRouteToPath.h:42
tuw_multi_robot_route_to_path::MultiRobotLocalBehaviorController::pubPath_
std::vector< ros::Publisher > pubPath_
Definition: MultiRobotLocalBehaviorController.h:57
tuw_multi_robot_route_to_path::MultiRobotLocalBehaviorController::subSegPath_
std::vector< ros::Subscriber > subSegPath_
Definition: MultiRobotLocalBehaviorController.h:59
tuw_multi_robot_route_to_path::MultiRobotLocalBehaviorController::findRobotId
int findRobotId(std::string _name)
Definition: MultiRobotLocalBehaviorController.cpp:176
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
tuw_multi_robot_route_to_path::PathSegment
Definition: RobotStateObserver.h:37
tuw_multi_robot_route_to_path::MultiRobotLocalBehaviorController::publishRobotInfo
void publishRobotInfo()
Definition: MultiRobotLocalBehaviorController.cpp:248
ros.h
tuw_multi_robot_route_to_path::MultiRobotLocalBehaviorController::robot_steps_
std::vector< int > robot_steps_
Definition: MultiRobotLocalBehaviorController.h:80
main
int main(int argc, char **argv)
Definition: MultiRobotLocalBehaviorController.cpp:31
tuw_multi_robot_route_to_path::MultiRobotLocalBehaviorController::robotDefaultRadius_
float robotDefaultRadius_
Definition: MultiRobotLocalBehaviorController.h:71
ros::spinOnce
ROSCPP_DECL void spinOnce()
tuw_multi_robot_route_to_path::PathSegment::start
Eigen::Vector2d start
Definition: RobotStateObserver.h:39
tuw_multi_robot_route_to_path::PathSegment::width
float width
Definition: RobotStateObserver.h:41
tuw_multi_robot_route_to_path::MultiRobotLocalBehaviorController::subOdometry_
std::vector< ros::Subscriber > subOdometry_
Definition: MultiRobotLocalBehaviorController.h:60
tuw_multi_robot_route_to_path::MultiRobotLocalBehaviorController::robot_pose_
std::vector< geometry_msgs::PoseWithCovariance > robot_pose_
Definition: MultiRobotLocalBehaviorController.h:70
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
tuw_multi_robot_route_to_path::PathSegment::goal
Eigen::Vector2d goal
Definition: RobotStateObserver.h:40
ros::ok
ROSCPP_DECL bool ok()
tuw_multi_robot_route_to_path::MultiRobotLocalBehaviorController::converter_
std::vector< RobotRouteToPath > converter_
Definition: MultiRobotLocalBehaviorController.h:77
tuw_multi_robot_route_to_path::MultiRobotLocalBehaviorController::observer_
std::vector< RobotStateObserver > observer_
Definition: MultiRobotLocalBehaviorController.h:78
tuw_multi_robot_route_to_path::MultiRobotLocalBehaviorController::robot_radius_
std::vector< float > robot_radius_
Definition: MultiRobotLocalBehaviorController.h:69
tuw_multi_robot_route_to_path::PathPrecondition::step
int step
Definition: RobotRouteToPath.h:40
tuw_multi_robot_route_to_path::MultiRobotLocalBehaviorController::frame_map_
std::string frame_map_
Definition: MultiRobotLocalBehaviorController.h:67
tuw_multi_robot_route_to_path::PathPrecondition
Definition: RobotRouteToPath.h:37
MultiRobotLocalBehaviorController.h
tuw_multi_robot_route_to_path::MultiRobotLocalBehaviorController::subOdomCb
void subOdomCb(const ros::MessageEvent< nav_msgs::Odometry const > &_event, int _topic)
Definition: MultiRobotLocalBehaviorController.cpp:121
tuw_multi_robot_route_to_path::MultiRobotLocalBehaviorController::topic_robot_info_
std::string topic_robot_info_
Definition: MultiRobotLocalBehaviorController.h:66
ros::Rate::sleep
bool sleep()
tuw_multi_robot_route_to_path::MultiRobotLocalBehaviorController::no_robots_
int no_robots_
Definition: MultiRobotLocalBehaviorController.h:79
tuw_multi_robot_route_to_path::MultiRobotLocalBehaviorController::pubRobotInfo_
ros::Publisher pubRobotInfo_
Definition: MultiRobotLocalBehaviorController.h:58
tuw_multi_robot_route_to_path::MultiRobotLocalBehaviorController::topic_odom_
std::string topic_odom_
Definition: MultiRobotLocalBehaviorController.h:65
std
tuw_multi_robot_route_to_path::SyncedPathPoint::p
Eigen::Vector3d p
Definition: RobotRouteToPath.h:44
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
ros::Rate
tuw_multi_robot_route_to_path
Definition: LocalBehaviorControllerNode.h:46
ros::MessageEvent::getMessage
boost::shared_ptr< M > getMessage() const
tuw_multi_robot_route_to_path::MultiRobotLocalBehaviorController::MultiRobotLocalBehaviorController
MultiRobotLocalBehaviorController(ros::NodeHandle &n)
Definition: MultiRobotLocalBehaviorController.cpp:52
tuw_multi_robot_route_to_path::MultiRobotLocalBehaviorController::subSegPathCb
void subSegPathCb(const ros::MessageEvent< tuw_multi_robot_msgs::Route const > &_event, int _topic)
Definition: MultiRobotLocalBehaviorController.cpp:187
ROS_INFO
#define ROS_INFO(...)
tuw_multi_robot_route_to_path::MultiRobotLocalBehaviorController::topic_route_
std::string topic_route_
Definition: MultiRobotLocalBehaviorController.h:64
tuw_multi_robot_route_to_path::MultiRobotLocalBehaviorController::topic_path_
std::string topic_path_
Definition: MultiRobotLocalBehaviorController.h:63
tuw_multi_robot_route_to_path::SyncedPathPoint::sync
std::vector< PathPrecondition > sync
Definition: RobotRouteToPath.h:45
ros::NodeHandle
ros::MessageEvent
tuw_multi_robot_route_to_path::MultiRobotLocalBehaviorController
Definition: MultiRobotLocalBehaviorController.h:42
tuw_multi_robot_route_to_path::MultiRobotLocalBehaviorController::publishPath
void publishPath(std::vector< Eigen::Vector3d > _p, int _topic)
Definition: MultiRobotLocalBehaviorController.cpp:145
ros::Time::now
static Time now()
tuw_multi_robot_route_to_path::PathPrecondition::robot_no
int robot_no
Definition: RobotRouteToPath.h:39


tuw_multi_robot_local_behavior_controller
Author(s): Benjamin Binder
autogenerated on Wed Mar 2 2022 01:10:04