#include <occupancy_grid.h>
Public Member Functions | |
| void | addPointsUnstamped (const hrl_msgs::FloatArrayBare pts_fab) |
| add list of points (in a ROS FloatArrayBare structure) to the occupancy grid. Not worrying about timestamps for now. length of pts_fab is 3N for N points. | |
| void | addPointsUnstamped (const std::vector< double > pts_vec) |
| add list of points (in a std vector of doubles) to the occupancy grid. Not worrying about timestamps for now. length of pts_vec is 3N for N points. | |
| uint32_t * | getOccupancyCountArray () |
| unsigned int | nX () |
| unsigned int | nY () |
| unsigned int | nZ () |
| OccupancyGrid (float center_x, float center_y, float center_z, float size_x, float size_y, float size_z, float res_x, float res_y, float res_z) | |
| Constructor for a voxel grid. | |
| void | publishMarkerArray_simple () |
| cube markers for cells that have occupancy count >=1 | |
| ~OccupancyGrid () | |
Private Member Functions | |
| bool | addPointsUnstamped_srv (hrl_srvs::FloatArray_None::Request &req, hrl_srvs::FloatArray_None::Response &res) |
| void | publishMarkerArray_simple_cb (const std_msgs::Empty::ConstPtr &msg) |
Private Attributes | |
| float | center_x_ |
| float | center_y_ |
| float | center_z_ |
| ros::Publisher | marker_pub_ |
| ros::NodeHandle | nh_ |
| unsigned int | nx_ |
| unsigned int | ny_ |
| unsigned int | nz_ |
| uint32_t * | occupancy_count_array_ |
| float | res_x_ |
| float | res_y_ |
| float | res_z_ |
| float | size_x_ |
| float | size_y_ |
| float | size_z_ |
| ros::ServiceServer | srv_add_points_unstamped_ |
| ros::Subscriber | sub_cmd_viz_simple_ |
Definition at line 24 of file occupancy_grid.h.
| OccupancyGrid::OccupancyGrid | ( | float | center_x, |
| float | center_y, | ||
| float | center_z, | ||
| float | size_x, | ||
| float | size_y, | ||
| float | size_z, | ||
| float | res_x, | ||
| float | res_y, | ||
| float | res_z | ||
| ) |
Constructor for a voxel grid.
| center_{x,y,z} | coordinates of the center of the grid |
| size_{x,y,z} | size of VOI (in meters) |
| res_{x,y,z} | resolution along the three directions |
Definition at line 16 of file occupancy_grid.cpp.
Definition at line 144 of file occupancy_grid.cpp.
| void OccupancyGrid::addPointsUnstamped | ( | const hrl_msgs::FloatArrayBare | pts_fab | ) |
add list of points (in a ROS FloatArrayBare structure) to the occupancy grid. Not worrying about timestamps for now. length of pts_fab is 3N for N points.
Definition at line 55 of file occupancy_grid.cpp.
| void OccupancyGrid::addPointsUnstamped | ( | const std::vector< double > | pts_vec | ) |
add list of points (in a std vector of doubles) to the occupancy grid. Not worrying about timestamps for now. length of pts_vec is 3N for N points.
Definition at line 60 of file occupancy_grid.cpp.
| bool OccupancyGrid::addPointsUnstamped_srv | ( | hrl_srvs::FloatArray_None::Request & | req, |
| hrl_srvs::FloatArray_None::Response & | res | ||
| ) | [private] |
Definition at line 134 of file occupancy_grid.cpp.
| uint32_t * OccupancyGrid::getOccupancyCountArray | ( | ) |
Definition at line 164 of file occupancy_grid.cpp.
| unsigned int OccupancyGrid::nX | ( | ) |
Definition at line 149 of file occupancy_grid.cpp.
| unsigned int OccupancyGrid::nY | ( | ) |
Definition at line 154 of file occupancy_grid.cpp.
| unsigned int OccupancyGrid::nZ | ( | ) |
Definition at line 159 of file occupancy_grid.cpp.
cube markers for cells that have occupancy count >=1
Definition at line 85 of file occupancy_grid.cpp.
| void OccupancyGrid::publishMarkerArray_simple_cb | ( | const std_msgs::Empty::ConstPtr & | msg | ) | [private] |
Definition at line 129 of file occupancy_grid.cpp.
float occupancy_grid::OccupancyGrid::center_x_ [private] |
Definition at line 71 of file occupancy_grid.h.
float occupancy_grid::OccupancyGrid::center_y_ [private] |
Definition at line 71 of file occupancy_grid.h.
float occupancy_grid::OccupancyGrid::center_z_ [private] |
Definition at line 71 of file occupancy_grid.h.
Definition at line 79 of file occupancy_grid.h.
Definition at line 76 of file occupancy_grid.h.
unsigned int occupancy_grid::OccupancyGrid::nx_ [private] |
Definition at line 69 of file occupancy_grid.h.
unsigned int occupancy_grid::OccupancyGrid::ny_ [private] |
Definition at line 69 of file occupancy_grid.h.
unsigned int occupancy_grid::OccupancyGrid::nz_ [private] |
Definition at line 69 of file occupancy_grid.h.
uint32_t* occupancy_grid::OccupancyGrid::occupancy_count_array_ [private] |
Definition at line 73 of file occupancy_grid.h.
float occupancy_grid::OccupancyGrid::res_x_ [private] |
Definition at line 72 of file occupancy_grid.h.
float occupancy_grid::OccupancyGrid::res_y_ [private] |
Definition at line 72 of file occupancy_grid.h.
float occupancy_grid::OccupancyGrid::res_z_ [private] |
Definition at line 72 of file occupancy_grid.h.
float occupancy_grid::OccupancyGrid::size_x_ [private] |
Definition at line 70 of file occupancy_grid.h.
float occupancy_grid::OccupancyGrid::size_y_ [private] |
Definition at line 70 of file occupancy_grid.h.
float occupancy_grid::OccupancyGrid::size_z_ [private] |
Definition at line 70 of file occupancy_grid.h.
Definition at line 78 of file occupancy_grid.h.
Definition at line 77 of file occupancy_grid.h.