The ROS node implementation that provides the tinySLAM method. More...
#include <iostream>
#include <ros/ros.h>
#include <sensor_msgs/LaserScan.h>
#include <memory>
#include <nav_msgs/OccupancyGrid.h>
#include "../core/sensor_data.h"
#include "../ros/topic_with_transform.h"
#include "../ros/rviz_grid_viewer.h"
#include "../ros/utils.h"
#include "../core/maps/area_occupancy_estimator.h"
#include "../core/maps/const_occupancy_estimator.h"
#include "../core/maps/grid_cell_strategy.h"
#include "tiny_fascade.h"
#include "tiny_world.h"
#include "tiny_grid_cells.h"
Go to the source code of this file.
Classes | |
class | PoseScanMatcherObserver |
Derived class from GridScanMatcherObserver to publish the robot pose. More... | |
Functions | |
std::shared_ptr< GridCellFactory > | init_cell_factory (TinyWorldParams ¶ms) |
TinyWorldParams | init_common_world_params () |
void | init_constants_for_ros (double &ros_tf_buffer_size, double &ros_map_rate, int &ros_filter_queue, int &ros_subscr_queue) |
void | init_frame_names (std::string &frame_odom, std::string &frame_robot_pose) |
GridMapParams | init_grid_map_params () |
std::shared_ptr< CellOccupancyEstimator > | init_occ_estimator () |
bool | init_skip_exceeding_lsr () |
int | main (int argc, char **argv) |
The ROS node implementation that provides the tinySLAM method.
There are an entry point and functions which parse the initialization file.
There is also a declaration of one class (PoseScanMatcherObserver is inherited from GridScanMatcherObserver).
Definition in file tiny_slam.cpp.
std::shared_ptr<GridCellFactory> init_cell_factory | ( | TinyWorldParams & | params | ) |
Determines the cell factory based on parameters came from a launch file.
[in] | params | - values from the launch file. |
Definition at line 69 of file tiny_slam.cpp.
TinyWorldParams init_common_world_params | ( | ) |
Initializes constants for scan matcher
Definition at line 125 of file tiny_slam.cpp.
void init_constants_for_ros | ( | double & | ros_tf_buffer_size, |
double & | ros_map_rate, | ||
int & | ros_filter_queue, | ||
int & | ros_subscr_queue | ||
) |
Initializes constants for ros utils
Definition at line 154 of file tiny_slam.cpp.
void init_frame_names | ( | std::string & | frame_odom, |
std::string & | frame_robot_pose | ||
) |
Definition at line 164 of file tiny_slam.cpp.
GridMapParams init_grid_map_params | ( | ) |
Initializes constants for map
Definition at line 141 of file tiny_slam.cpp.
std::shared_ptr<CellOccupancyEstimator> init_occ_estimator | ( | ) |
Determines the estimator based on parameters came from a launch file.
[in] | params | - values from a launch file. |
Definition at line 92 of file tiny_slam.cpp.
bool init_skip_exceeding_lsr | ( | ) |
Returns how to deal with exceeding values based on parameters came from a launch file.
Definition at line 115 of file tiny_slam.cpp.
int main | ( | int | argc, |
char ** | argv | ||
) |
The entry point: creates an environment world and the main node "tiny slam".
Definition at line 172 of file tiny_slam.cpp.