Decision Module
1.0
ICRA2020 AI Challenge Northwestern Polytechnical University Aoxiang Team Strategy Code
|
Go to the documentation of this file.
6 #include "roborts_msgs/BuffZoneStatus.h"
7 #include "../../roborts_common/math/geometry.h"
17 Field(
const ros::NodeHandle &nh = ros::NodeHandle(
"~"));
21 static std::shared_ptr<Field>
GetField();
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) ;
38 std::vector<roborts_common::Polygon2D>
46 static std::shared_ptr<Field>
field_;
52 std::vector<roborts_common::Zone>
walls_;
ros::NodeHandle nh_
Definition: field.h:47
static std::shared_ptr< Field > field_
Definition: field.h:46
int IsZoneActive(BuffStatus buff_status)
Definition: field.cpp:199
BuffStatus
Definition: blackboard_common.h:61
Field(const Field &)=delete
std::vector< std::pair< BuffZoneStatus, roborts_common::Zone > > vec_buff_zone_status_
Definition: field.h:50
Definition: behavior_test_node.h:14
const std::vector< roborts_common::Zone > & getObstacles() const
Definition: field.cpp:165
bool GetDisToObstacleSuitable(const roborts_common::Point2D &point)
Definition: field.cpp:233
static std::shared_ptr< Field > GetField()
Definition: field.cpp:281
const std::vector< roborts_common::Zone > & getWalls() const
Definition: field.cpp:169
ros::Subscriber buff_zone_sub_
Definition: field.h:48
std::vector< roborts_common::Zone > walls_
Definition: field.h:52
static std::vector< roborts_common::Polygon2D > TurnRectangulars(const std::vector< roborts_common::Zone > &zones)
Definition: field.cpp:173
std::vector< roborts_common::Zone > obstacles_
Definition: field.h:51
void buffZoneStatusCallback(const roborts_msgs::BuffZoneStatus::ConstPtr &msg)
Definition: field.cpp:254
std::vector< roborts_common::Polygon2D > GetObstaclesBetweenTwoRobots(const roborts_common::Point2D point1, const roborts_common::Point2D point2)
Definition: field.cpp:210
const std::vector< std::pair< BuffZoneStatus, roborts_common::Zone > > & GetBuffZoneStatus() const
Definition: field.cpp:161
Field(const ros::NodeHandle &nh=ros::NodeHandle("~"))
Definition: field.cpp:12