Namespaces | Enumerations | Functions | Variables
LaserScanInterpreter.h File Reference
#include <ros/ros.h>
#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>
#include <sensor_msgs/LaserScan.h>
#include <find_moving_objects/bank.h>
#include "laserscan_interpreter_default_parameter_values.h"
Include dependency graph for LaserScanInterpreter.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

 find_moving_objects
 

Enumerations

enum  find_moving_objects::state_t {
  find_moving_objects::WAIT_FOR_FIRST_MESSAGE_HZ, find_moving_objects::CALCULATE_HZ, find_moving_objects::INIT_BANKS, find_moving_objects::FIND_MOVING_OBJECTS,
  find_moving_objects::WAIT_FOR_FIRST_MESSAGE_HZ, find_moving_objects::CALCULATE_HZ, find_moving_objects::INIT_BANKS, find_moving_objects::FIND_MOVING_OBJECTS
}
 

Functions

void find_moving_objects::laserScanCallback (const sensor_msgs::LaserScan::ConstPtr &msg)
 

Variables

std::vector< BankArgument > find_moving_objects::bank_arguments
 
std::vector< Bank * > find_moving_objects::banks
 
const double find_moving_objects::default_base_confidence = 0.5
 
const std::string find_moving_objects::default_base_frame = "base_link"
 
const double find_moving_objects::default_delta_width_confidence_decrease_factor = 0.5
 
const double find_moving_objects::default_ema_alpha = 1.0
 
const std::string find_moving_objects::default_fixed_frame = "odom"
 
const std::string find_moving_objects::default_map_frame = "map"
 
const double find_moving_objects::default_max_confidence_for_dt_match = 0.5
 
const int find_moving_objects::default_nr_scans_in_bank = 0
 
const std::string find_moving_objects::default_ns_delta_position_lines = "delta_position_lines"
 
const std::string find_moving_objects::default_ns_velocity_arrows = "velocity_arrows"
 
const std::string find_moving_objects::default_ns_width_lines = "width_lines"
 
const double find_moving_objects::default_object_threshold_bank_tracking_max_delta_distance = 0.4
 
const double find_moving_objects::default_object_threshold_edge_max_delta_range = 0.15
 
const int find_moving_objects::default_object_threshold_max_delta_width_in_points = 15
 
const double find_moving_objects::default_object_threshold_max_distance = 6.5
 
const double find_moving_objects::default_object_threshold_min_confidence = 0.7
 
const int find_moving_objects::default_object_threshold_min_nr_points = 3
 
const double find_moving_objects::default_object_threshold_min_speed = 0.1
 
const double find_moving_objects::default_optimize_nr_scans_in_bank = 0.3
 
const int find_moving_objects::default_publish_buffer_size = 1
 
const bool find_moving_objects::default_publish_ema = true
 
const bool find_moving_objects::default_publish_objects = true
 
const bool find_moving_objects::default_publish_objects_closest_points_markers = true
 
const bool find_moving_objects::default_publish_objects_delta_position_lines = true
 
const bool find_moving_objects::default_publish_objects_velocity_arrows = true
 
const bool find_moving_objects::default_publish_objects_width_lines = true
 
const int find_moving_objects::default_subscribe_buffer_size = 1
 
const std::string find_moving_objects::default_topic_ema = "ema"
 
const std::string find_moving_objects::default_topic_objects = "moving_objects"
 
const std::string find_moving_objects::default_topic_objects_closest_points_markers = "objects_closest_point_markers"
 
const std::string find_moving_objects::default_topic_objects_delta_position_lines = "objects_delta_position_lines"
 
const std::string find_moving_objects::default_topic_objects_velocity_arrows = "objects_velocity_arrows"
 
const std::string find_moving_objects::default_topic_objects_width_lines = "objects_width_lines"
 
const bool find_moving_objects::default_velocity_arrows_use_base_frame = false
 
const bool find_moving_objects::default_velocity_arrows_use_fixed_frame = false
 
const bool find_moving_objects::default_velocity_arrows_use_full_gray_scale = false
 
const bool find_moving_objects::default_velocity_arrows_use_sensor_frame = false
 
double find_moving_objects::max_confidence_for_dt_match
 
const int find_moving_objects::max_messages = 100
 
const double find_moving_objects::max_time = 1.5
 
ros::NodeHandle find_moving_objects::nh
 
ros::NodeHandle find_moving_objects::nh_priv
 
double find_moving_objects::optimize_nr_scans_in_bank
 
int find_moving_objects::received_messages
 
double find_moving_objects::start_time
 
state_t find_moving_objects::state
 
int find_moving_objects::subscribe_buffer_size
 
std::string find_moving_objects::subscribe_topic
 
tf2_ros::Bufferfind_moving_objects::tf_buffer = new tf2_ros::Buffer
 
tf2_ros::MessageFilter< sensor_msgs::LaserScan > * find_moving_objects::tf_filter = new tf2_ros::MessageFilter<sensor_msgs::LaserScan>(*tf_subscriber, *tf_buffer, "", subscribe_buffer_size, 0)
 
std::vector< std::string > find_moving_objects::tf_filter_target_frames
 
tf2_ros::TransformListenerfind_moving_objects::tf_listener = new tf2_ros::TransformListener(*tf_buffer)
 
message_filters::Subscriber< sensor_msgs::LaserScan > * find_moving_objects::tf_subscriber = new message_filters::Subscriber<sensor_msgs::LaserScan>()
 


find_moving_objects
Author(s): Andreas Gustavsson
autogenerated on Mon Jun 10 2019 13:13:19