MultiRobotLocalBehaviorController.h
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 
27 #ifndef TUW_MULTI_ROBOT_ROUTE_TO_PATH_H
28 #define TUW_MULTI_ROBOT_ROUTE_TO_PATH_H
29 
30 // ROS
31 #include <ros/ros.h>
32 #include <nav_msgs/Path.h>
33 #include <nav_msgs/Odometry.h>
34 #include <tuw_multi_robot_msgs/Route.h>
37 
38 #include <memory>
39 
41 {
43 {
44  //special class-member functions.
45 public:
47 
48  //ROS:
51  std::unique_ptr<ros::Rate> rate_;
52  void publishRobotInfo();
53 
54 private:
55  void publishPath(std::vector<Eigen::Vector3d> _p, int _topic);
56 
57  std::vector<ros::Publisher> pubPath_;
59  std::vector<ros::Subscriber> subSegPath_;
60  std::vector<ros::Subscriber> subOdometry_;
61 
62  // ROS Topic names
63  std::string topic_path_;
64  std::string topic_route_;
65  std::string topic_odom_;
66  std::string topic_robot_info_;
67  std::string frame_map_;
68  std::vector<std::string> robot_names_;
69  std::vector<float> robot_radius_;
70  std::vector<geometry_msgs::PoseWithCovariance> robot_pose_;
71  float robotDefaultRadius_ = 0.6;
72 
73  void subOdomCb(const ros::MessageEvent<nav_msgs::Odometry const> &_event, int _topic);
75  int findRobotId(std::string _name);
76 
77  std::vector<RobotRouteToPath> converter_;
78  std::vector<RobotStateObserver> observer_;
80  std::vector<int> robot_steps_;
81 };
82 
83 } // namespace tuw_multi_robot_route_to_path
84 
85 #endif
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)


tuw_multi_robot_local_behavior_controller
Author(s): Benjamin Binder
autogenerated on Mon Jun 10 2019 15:42:36