-
Notifications
You must be signed in to change notification settings - Fork 2
/
Copy pathparameters.h
57 lines (51 loc) · 1.48 KB
/
parameters.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
#ifndef _OCCUPANCY_MAP_PARAMETERS_H_
#define _OCCUPANCY_MAP_PARAMETERS_H_
#include <Eigen/Eigen>
#include <ros/ros.h>
#include <string>
struct Parameters
{
// resolution (in meters)
double resolution;
// boundary and size of map in vector form
Eigen::Vector3d bottom_left;
Eigen::Vector3d upper_right;
Eigen::Vector3d map_size;
// probabilty parameters for probabilistic occupancy map
double prob_hit;
double prob_miss;
double prob_occupancy;
double prob_min;
double prob_max;
// parameters for ray casting
double min_ray_length;
double max_ray_length;
// intrinsic parameters of camera
double center_x;
double center_y;
double focal_length_x;
double focal_length_y;
// depth filter for depth images
bool use_depth_filter;
double filter_max_depth;
double filter_min_depth;
double filter_tolerance;
int depth_filter_margin;
// transformation from camera to body frame
Eigen::Matrix4d T_Body_Camera;
Eigen::Matrix4d T_D_B;
// update frequency
double update_occupancy_every_n_sec;
// visualization frequency
int visualize_every_n_updates;
// global
bool global_update;
bool global_map;
bool global_vis;
// map margin for visualization
Eigen::Vector3d vis_min_margin, vis_max_margin;
// publishing sensor_msgs::PointCloud header frame id
std::string map_frame_id;
};
void SetNodeParameters(Parameters& parameters, const ros::NodeHandle& node);
#endif