A terrain map publishing class.
More...
#include <terrain_map_publisher.h>
|
| TerrainMapPublisher (ros::NodeHandle nh) |
| Constructor for TerrainMapPublisher Class.
|
|
void | updateParams () |
| Updates the terrain_map_publisher parameters.
|
|
void | createMap () |
| Creates the map object from scratch.
|
|
void | updateMap () |
| Updates the map object with params.
|
|
std::vector< std::vector< double > > | loadCSV (std::string filename) |
| Loads data from a specified CSV file into a nested std::vector structure.
|
|
void | loadMapFromCSV () |
| Loads data into the map object from a CSV.
|
|
void | loadMapFromImage (const sensor_msgs::Image &msg) |
| Loads data into the map object from an image topic.
|
|
void | publishMap () |
| Publishes map data to the terrain_map topic.
|
|
void | spin () |
| Calls ros spinOnce and pubs data at set frequency.
|
|
|
ros::Subscriber | image_sub_ |
| ROS Subscriber for image data.
|
|
ros::Publisher | terrain_map_pub_ |
| ROS Publisher for the terrain map.
|
|
ros::NodeHandle | nh_ |
| Nodehandle to pub to and sub from.
|
|
double | update_rate_ |
|
std::string | map_frame_ |
| Handle for the map frame.
|
|
grid_map::GridMap | terrain_map_ |
| grid_map::GridMap object for terrain data
|
|
std::string | terrain_type_ |
| String for the terrain file name.
|
|
std::string | map_data_source_ |
| string of the source of the terrain map data
|
|
bool | map_initialized_ = false |
| bool to flag if the map has been initialized yet
|
|
double | resolution_ |
| double for map resolution
|
|
double | min_height_ |
| double for map resolution
|
|
double | max_height_ |
| double for map resolution
|
|
Obstacle | obstacle_ |
| Obstacle object.
|
|
Step | step1_ |
| Step 1 object.
|
|
Step | step2_ |
| Step 2 object.
|
|
A terrain map publishing class.
TerrainMapPublisher is a class for publishing terrain maps from a variety of sources, including from scratch.
◆ TerrainMapPublisher()
TerrainMapPublisher::TerrainMapPublisher |
( |
ros::NodeHandle |
nh | ) |
|
◆ loadCSV()
std::vector< std::vector< double > > TerrainMapPublisher::loadCSV |
( |
std::string |
filename | ) |
|
Loads data from a specified CSV file into a nested std::vector structure.
- Parameters
-
[in] | filename | Path to the CSV file |
- Returns
- Data from the CSV in vector structure
◆ loadMapFromImage()
void TerrainMapPublisher::loadMapFromImage |
( |
const sensor_msgs::Image & |
msg | ) |
|
Loads data into the map object from an image topic.
- Parameters
-
◆ update_rate_
double TerrainMapPublisher::update_rate_ |
|
private |
Update rate for sending and receiving data, unused since pubs are called in callbacks
The documentation for this class was generated from the following files: