#include <laser_simulator.h>
|
| | LaserScannerSimulator (ros::NodeHandle *nh) |
| |
| void | set_laser_params (std::string frame_id, double fov, unsigned int beam_count, double max_range, double min_range, double l_frequency) |
| |
| void | set_noise_params (bool use_model, double sigma_hit_reading, double lambda_short_reading, double z_hit, double z_short, double z_max, double z_rand) |
| |
| void | start () |
| |
| void | stop () |
| |
| | ~LaserScannerSimulator () |
| |
|
| double | apply_range_noise (double range_reading) |
| |
| double | find_map_range (double x, double y, double theta) |
| |
| void | get_laser_pose (double *x, double *y, double *theta) |
| |
| void | get_map () |
| |
| void | get_map2world_coordinates (int map_x, int map_y, double *x, double *y) |
| |
| int | get_map_occupancy (int x, int y) |
| |
| void | get_params () |
| |
| void | get_world2map_coordinates (double x, double y, int *map_x, int *map_y) |
| |
| void | update_loop (const ros::TimerEvent &event) |
| |
| void | update_scan (double x, double y, double theta) |
| |
Definition at line 17 of file laser_simulator.h.
◆ LaserScannerSimulator()
◆ ~LaserScannerSimulator()
| LaserScannerSimulator::~LaserScannerSimulator |
( |
| ) |
|
◆ apply_range_noise()
| double LaserScannerSimulator::apply_range_noise |
( |
double |
range_reading | ) |
|
|
private |
◆ find_map_range()
| double LaserScannerSimulator::find_map_range |
( |
double |
x, |
|
|
double |
y, |
|
|
double |
theta |
|
) |
| |
|
private |
raytracing, calculates intersection with the map for a single ray
Definition at line 156 of file laser_simulator.cpp.
◆ get_laser_pose()
| void LaserScannerSimulator::get_laser_pose |
( |
double * |
x, |
|
|
double * |
y, |
|
|
double * |
theta |
|
) |
| |
|
private |
◆ get_map()
| void LaserScannerSimulator::get_map |
( |
| ) |
|
|
private |
◆ get_map2world_coordinates()
| void LaserScannerSimulator::get_map2world_coordinates |
( |
int |
map_x, |
|
|
int |
map_y, |
|
|
double * |
x, |
|
|
double * |
y |
|
) |
| |
|
private |
◆ get_map_occupancy()
| int LaserScannerSimulator::get_map_occupancy |
( |
int |
x, |
|
|
int |
y |
|
) |
| |
|
private |
◆ get_params()
| void LaserScannerSimulator::get_params |
( |
| ) |
|
|
private |
◆ get_world2map_coordinates()
| void LaserScannerSimulator::get_world2map_coordinates |
( |
double |
x, |
|
|
double |
y, |
|
|
int * |
map_x, |
|
|
int * |
map_y |
|
) |
| |
|
private |
◆ set_laser_params()
| void LaserScannerSimulator::set_laser_params |
( |
std::string |
frame_id, |
|
|
double |
fov, |
|
|
unsigned int |
beam_count, |
|
|
double |
max_range, |
|
|
double |
min_range, |
|
|
double |
l_frequency |
|
) |
| |
◆ set_noise_params()
| void LaserScannerSimulator::set_noise_params |
( |
bool |
use_model, |
|
|
double |
sigma_hit_reading, |
|
|
double |
lambda_short_reading, |
|
|
double |
z_hit, |
|
|
double |
z_short, |
|
|
double |
z_max, |
|
|
double |
z_rand |
|
) |
| |
◆ start()
| void LaserScannerSimulator::start |
( |
| ) |
|
◆ stop()
| void LaserScannerSimulator::stop |
( |
| ) |
|
◆ update_loop()
◆ update_scan()
| void LaserScannerSimulator::update_scan |
( |
double |
x, |
|
|
double |
y, |
|
|
double |
theta |
|
) |
| |
|
private |
updates the laser scan based on current 2D pose of the scanner in map coordinates
Definition at line 120 of file laser_simulator.cpp.
◆ have_map
| bool LaserScannerSimulator::have_map |
|
private |
◆ is_running
| bool LaserScannerSimulator::is_running |
|
private |
◆ l_beams
| int LaserScannerSimulator::l_beams |
|
private |
◆ l_fov
| double LaserScannerSimulator::l_fov |
|
private |
◆ l_frame
| std::string LaserScannerSimulator::l_frame |
|
private |
◆ l_frequency
| double LaserScannerSimulator::l_frequency |
|
private |
◆ l_max_range
| double LaserScannerSimulator::l_max_range |
|
private |
◆ l_min_range
| double LaserScannerSimulator::l_min_range |
|
private |
◆ l_scan_topic
| std::string LaserScannerSimulator::l_scan_topic |
|
private |
◆ lambda_short
| double LaserScannerSimulator::lambda_short |
|
private |
◆ laser_pub
◆ loop_timer
◆ map
| nav_msgs::OccupancyGrid LaserScannerSimulator::map |
|
private |
◆ map_service
| std::string LaserScannerSimulator::map_service |
|
private |
◆ nh_ptr
◆ output_scan
| sensor_msgs::LaserScan LaserScannerSimulator::output_scan |
|
private |
◆ p_hit
| std::normal_distribution<double> LaserScannerSimulator::p_hit |
|
private |
◆ p_rand
| std::uniform_real_distribution<double> LaserScannerSimulator::p_rand |
|
private |
◆ p_short
| std::exponential_distribution<double> LaserScannerSimulator::p_short |
|
private |
◆ rand_gen
| std::default_random_engine LaserScannerSimulator::rand_gen |
|
private |
◆ rob_laser_tf
◆ selector
| std::uniform_real_distribution<double> LaserScannerSimulator::selector |
|
private |
◆ sigma_hit
| double LaserScannerSimulator::sigma_hit |
|
private |
◆ tl
◆ use_noise_model
| bool LaserScannerSimulator::use_noise_model |
|
private |
◆ z_mix
| double LaserScannerSimulator::z_mix[4] |
|
private |
The documentation for this class was generated from the following files: