tiny_slam.cpp
Go to the documentation of this file.
1 #include <iostream>
2 #include <ros/ros.h>
3 #include <sensor_msgs/LaserScan.h>
4 #include <memory>
5 
6 #include <nav_msgs/OccupancyGrid.h>
7 
8 #include "../../ros/topic_with_transform.h"
9 #include "../../ros/laser_scan_observer.h"
10 #include "../../ros/init_utils.h"
11 
12 #include "../../ros/launch_properties_provider.h"
13 #include "init_tiny_slam.h"
14 
15 using ObservT = sensor_msgs::LaserScan;
17 
18 int main(int argc, char** argv) {
19  ros::init(argc, argv, "tinySLAM");
20 
21  auto props = LaunchPropertiesProvider{};
22  auto slam = init_tiny_slam(props);
23 
24  // connect the slam to a ros-topic based data provider
25  // FIXME: viny_slam.cpp code duplication
26  ros::NodeHandle nh;
27  double ros_map_publishing_rate, ros_tf_buffer_size;
28  int ros_filter_queue, ros_subscr_queue;
29  init_constants_for_ros(ros_tf_buffer_size, ros_map_publishing_rate,
30  ros_filter_queue, ros_subscr_queue);
31  auto scan_provider = std::make_unique<TopicWithTransform<ObservT>>(
33  ros_tf_buffer_size, ros_filter_queue, ros_subscr_queue
34  );
35 
36  auto occup_grid_pub_pin = create_occupancy_grid_publisher<TinySlamMap>(
37  slam.get(), nh, ros_map_publishing_rate);
38 
39  auto pose_pub_pin = create_pose_correction_tf_publisher<ObservT, TinySlamMap>(
40  slam.get(), scan_provider.get(), props);
41  auto rp_pub_pin = create_robot_pose_tf_publisher<TinySlamMap>(slam.get());
42 
43  auto scan_obs = std::make_shared<LaserScanObserver>(
44  slam, get_skip_exceeding_lsr(props), get_use_trig_cache(props));
45  // NB: pose_pub_pin must be subscribed first
46  scan_provider->subscribe(scan_obs);
47 
48  ros::spin();
49 }
std::string laser_scan_2D_ros_topic_name(const PropertiesProvider &props)
Definition: init_utils.h:25
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool get_use_trig_cache(const PropertiesProvider &props)
Definition: init_utils.h:56
sensor_msgs::LaserScan ObservT
Definition: gmapping.cpp:15
int main(int argc, char **argv)
Definition: tiny_slam.cpp:18
auto init_tiny_slam(const PropertiesProvider &props)
ROSCPP_DECL void spin(Spinner &spinner)
std::string tf_odom_frame_id(const PropertiesProvider &props)
Definition: init_utils.h:29
void init_constants_for_ros(double &ros_tf_buffer_size, double &ros_map_rate, int &ros_filter_queue, int &ros_subscr_queue)
Definition: init_utils.h:138
TinySlam::MapType TinySlamMap
Definition: tiny_slam.cpp:16
bool get_skip_exceeding_lsr(const PropertiesProvider &props)
Definition: init_utils.h:49


slam_constructor
Author(s): JetBrains Research, OSLL team
autogenerated on Mon Jun 10 2019 15:08:25