Decision Module  1.0
ICRA2020 AI Challenge Northwestern Polytechnical University Aoxiang Team Strategy Code
field.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <vector>
4 #include <ros/ros.h>
5 
6 #include "roborts_msgs/BuffZoneStatus.h"
7 #include "../../roborts_common/math/geometry.h"
8 
9 #include "blackboard_common.h"
10 
11 namespace roborts_decision {
15 class Field {
16  public:
17  Field(const ros::NodeHandle &nh = ros::NodeHandle("~"));
18  Field(const Field&) = delete;
19  Field(Field &&) = delete;
20 
21  static std::shared_ptr<Field> GetField();
22 
23  // 获得障碍物、墙的信息
24  const std::vector<std::pair<BuffZoneStatus, roborts_common::Zone>> &GetBuffZoneStatus() const;
25  const std::vector<roborts_common::Zone> &getObstacles() const;
26  const std::vector<roborts_common::Zone> &getWalls() const;
27  static std::vector<roborts_common::Polygon2D> TurnRectangulars(const std::vector<roborts_common::Zone> &zones) ;
28 
35  int IsZoneActive(BuffStatus buff_status);
36 
37  //获取我方机器人与敌方机器人之间障碍物
38  std::vector<roborts_common::Polygon2D>
39  GetObstaclesBetweenTwoRobots(const roborts_common::Point2D point1, const roborts_common::Point2D point2);
40 
41  // 获取坐标点到障碍物的最短距离是否合适
42  bool GetDisToObstacleSuitable(const roborts_common::Point2D &point);
43 
44  private:
45 
46  static std::shared_ptr<Field> field_;
47  ros::NodeHandle nh_;
48  ros::Subscriber buff_zone_sub_;
49 
50  std::vector<std::pair<BuffZoneStatus, roborts_common::Zone>> vec_buff_zone_status_;
51  std::vector<roborts_common::Zone> obstacles_;
52  std::vector<roborts_common::Zone> walls_;
53 
54  void buffZoneStatusCallback(const roborts_msgs::BuffZoneStatus::ConstPtr &msg);
55 };
56 }
roborts_decision::Field::nh_
ros::NodeHandle nh_
Definition: field.h:47
roborts_decision::Field::field_
static std::shared_ptr< Field > field_
Definition: field.h:46
roborts_decision::Field::IsZoneActive
int IsZoneActive(BuffStatus buff_status)
Definition: field.cpp:199
roborts_decision::BuffStatus
BuffStatus
Definition: blackboard_common.h:61
roborts_decision::Field::Field
Field(const Field &)=delete
blackboard_common.h
roborts_decision::Field::vec_buff_zone_status_
std::vector< std::pair< BuffZoneStatus, roborts_common::Zone > > vec_buff_zone_status_
Definition: field.h:50
roborts_decision::Field
Definition: field.h:15
roborts_decision::Field::Field
Field(Field &&)=delete
roborts_decision
Definition: behavior_test_node.h:14
roborts_decision::Field::getObstacles
const std::vector< roborts_common::Zone > & getObstacles() const
Definition: field.cpp:165
roborts_decision::Field::GetDisToObstacleSuitable
bool GetDisToObstacleSuitable(const roborts_common::Point2D &point)
Definition: field.cpp:233
roborts_decision::Field::GetField
static std::shared_ptr< Field > GetField()
Definition: field.cpp:281
roborts_decision::Field::getWalls
const std::vector< roborts_common::Zone > & getWalls() const
Definition: field.cpp:169
roborts_decision::Field::buff_zone_sub_
ros::Subscriber buff_zone_sub_
Definition: field.h:48
roborts_decision::Field::walls_
std::vector< roborts_common::Zone > walls_
Definition: field.h:52
roborts_decision::Field::TurnRectangulars
static std::vector< roborts_common::Polygon2D > TurnRectangulars(const std::vector< roborts_common::Zone > &zones)
Definition: field.cpp:173
roborts_decision::Field::obstacles_
std::vector< roborts_common::Zone > obstacles_
Definition: field.h:51
roborts_decision::Field::buffZoneStatusCallback
void buffZoneStatusCallback(const roborts_msgs::BuffZoneStatus::ConstPtr &msg)
Definition: field.cpp:254
roborts_decision::Field::GetObstaclesBetweenTwoRobots
std::vector< roborts_common::Polygon2D > GetObstaclesBetweenTwoRobots(const roborts_common::Point2D point1, const roborts_common::Point2D point2)
Definition: field.cpp:210
roborts_decision::Field::GetBuffZoneStatus
const std::vector< std::pair< BuffZoneStatus, roborts_common::Zone > > & GetBuffZoneStatus() const
Definition: field.cpp:161
roborts_decision::Field::Field
Field(const ros::NodeHandle &nh=ros::NodeHandle("~"))
Definition: field.cpp:12