#include <social_layer.h>
|
| bool | isDiscretized () |
| |
| virtual void | onInitialize () |
| |
| | SocialLayer () |
| |
| virtual void | updateBounds (double origin_x, double origin_y, double origin_yaw, double *min_x, double *min_y, double *max_x, double *max_y) |
| |
| virtual void | updateBoundsFromPeople (double *min_x, double *min_y, double *max_x, double *max_y)=0 |
| |
| virtual void | updateCosts (costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)=0 |
| |
| virtual void | activate () |
| |
| virtual void | deactivate () |
| |
| const std::vector< geometry_msgs::Point > & | getFootprint () const |
| |
| std::string | getName () const |
| |
| void | initialize (LayeredCostmap *parent, std::string name, tf::TransformListener *tf) |
| |
| bool | isCurrent () const |
| |
| | Layer () |
| |
| virtual void | matchSize () |
| |
| virtual void | onFootprintChanged () |
| |
| virtual void | reset () |
| |
| virtual | ~Layer () |
| |
Definition at line 13 of file social_layer.h.
| social_navigation_layers::SocialLayer::SocialLayer |
( |
| ) |
|
|
inline |
| bool social_navigation_layers::SocialLayer::isDiscretized |
( |
| ) |
|
|
inline |
| void social_navigation_layers::SocialLayer::onInitialize |
( |
| ) |
|
|
virtual |
| void social_navigation_layers::SocialLayer::peopleCallback |
( |
const people_msgs::People & |
people | ) |
|
|
protected |
| void social_navigation_layers::SocialLayer::updateBounds |
( |
double |
origin_x, |
|
|
double |
origin_y, |
|
|
double |
origin_yaw, |
|
|
double * |
min_x, |
|
|
double * |
min_y, |
|
|
double * |
max_x, |
|
|
double * |
max_y |
|
) |
| |
|
virtual |
| virtual void social_navigation_layers::SocialLayer::updateBoundsFromPeople |
( |
double * |
min_x, |
|
|
double * |
min_y, |
|
|
double * |
max_x, |
|
|
double * |
max_y |
|
) |
| |
|
pure virtual |
| virtual void social_navigation_layers::SocialLayer::updateCosts |
( |
costmap_2d::Costmap2D & |
master_grid, |
|
|
int |
min_i, |
|
|
int |
min_j, |
|
|
int |
max_i, |
|
|
int |
max_j |
|
) |
| |
|
pure virtual |
| bool social_navigation_layers::SocialLayer::first_time_ |
|
protected |
| double social_navigation_layers::SocialLayer::last_max_x_ |
|
protected |
| double social_navigation_layers::SocialLayer::last_max_y_ |
|
protected |
| double social_navigation_layers::SocialLayer::last_min_x_ |
|
protected |
| double social_navigation_layers::SocialLayer::last_min_y_ |
|
protected |
| boost::recursive_mutex social_navigation_layers::SocialLayer::lock_ |
|
protected |
| ros::Duration social_navigation_layers::SocialLayer::people_keep_time_ |
|
protected |
| people_msgs::People social_navigation_layers::SocialLayer::people_list_ |
|
protected |
| std::list<people_msgs::Person> social_navigation_layers::SocialLayer::transformed_people_ |
|
protected |
The documentation for this class was generated from the following files: