28 #include <tf/transform_datatypes.h> 30 int main(
int argc,
char **argv)
52 robot_names_(
std::vector<
std::string>({
"robot_0",
"robot_1"}))
55 std::string robot_names_string =
"";
56 n_param_.
param(
"robot_names_str", robot_names_string, robot_names_string);
58 if (robot_names_string.size() > 0)
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);
66 while (std::getline(stringStr, result,
','))
107 const nav_msgs::Odometry_<std::allocator<void>>::ConstPtr &odom = _event.
getMessage();
109 Eigen::Vector2d pt(odom->pose.pose.position.x, odom->pose.pose.position.y);
111 bool changed =
false;
121 ROS_INFO(
"new path found %i %lu", i, newPath.size());
134 path.header.frame_id =
"map";
136 for (
const Eigen::Vector3d &p : _p)
138 geometry_msgs::PoseStamped ps;
141 ps.header.frame_id =
"map";
143 ps.pose.position.x = p[0];
144 ps.pose.position.y = p[1];
146 Eigen::Quaternion<float> q;
147 q = Eigen::AngleAxisf(p[2], Eigen::Vector3f::UnitZ());
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);
156 ROS_INFO(
"published path %i", _topic);
173 const tuw_multi_robot_msgs::Route_<std::allocator<void>>::ConstPtr &path = _event.
getMessage();
175 std::vector<SyncedPathPoint> localPath;
176 std::vector<PathSegment> segPath;
178 if (path->segments.size() == 0)
181 for (
const tuw_multi_robot_msgs::RouteSegment &seg : path->segments)
186 ps.
start[0] = seg.start.position.x;
187 ps.
start[1] = seg.start.position.y;
189 ps.
goal[0] = seg.end.position.x;
190 ps.
goal[1] = seg.end.position.y;
192 ps.
width = seg.width;
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);
200 spp.
p[0] = seg.end.position.x;
201 spp.
p[1] = seg.end.position.y;
204 for (
const tuw_multi_robot_msgs::RoutePrecondition &pc : seg.preconditions)
208 prec.
step = pc.current_route_segment;
210 spp.
sync.push_back(prec);
213 segPath.push_back(ps);
214 localPath.push_back(spp);
226 ROS_INFO(
"initial path found %i %lu", _topic, newPath.size());
std::vector< RobotStateObserver > observer_
void subSegPathCb(const ros::MessageEvent< tuw_multi_robot_msgs::Route const > &_event, int _topic)
std::vector< std::string > robot_names_
void subOdomCb(const ros::MessageEvent< nav_msgs::Odometry const > &_event, int _topic)
int findRobotId(std::string _name)
std::vector< ros::Subscriber > subSegPath_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::string topic_seg_path_
MultiRobotRouteToPathNode(ros::NodeHandle &n)
void publishPath(std::vector< Eigen::Vector3d > _p, int _topic)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
int main(int argc, char **argv)
std::vector< RobotRouteToPath > converter_
std::vector< int > robot_steps_
std::vector< PathPrecondition > sync
std::vector< ros::Publisher > pubPath_
ROSCPP_DECL void spinOnce()
boost::shared_ptr< M > getMessage() const
ros::NodeHandle n_param_
Node handler to the current node.
std::vector< ros::Subscriber > subOdometry_