6 std::shared_ptr<ScanParameters> params)
23 auto resp =
get_parameter(
"angular_fov",
"radial_range_min",
"radial_range_max",
"measure_start_angle",
24 "measure_stop_angle",
"scan_frequency");
30 params_->angle_min = start_stop.first;
31 params_->angle_max = start_stop.second;
38 param_server_R2300_ = std::make_unique<dynamic_reconfigure::Server<pf_driver::PFDriverR2300Config>>();
48 std::vector<bool> enabled_layers(vals.size(),
false);
49 for (
int i = 0; i < vals.size(); i++)
51 if (vals[i].compare(
"on") == 0)
61 float measure_start_angle =
get_parameter_float(
"measure_start_angle") / 10000.0 * M_PI / 180.0;
62 float measure_stop_angle =
get_parameter_float(
"measure_stop_angle") / 10000.0 * M_PI / 180.0;
63 start_angle = start_angle * M_PI / 180.0;
67 return std::pair<float, float>(measure_start_angle, measure_stop_angle);
72 return std::string(
"start_angle");
113 else if (level == 10)
117 else if (level == 11)
121 else if (level == 12)
125 else if (level == 13)
129 else if (level == 14)
133 else if (level == 15)
137 else if (level == 18)
141 else if (level == 19)
146 else if (level == 20)
148 config_->watchdog = (
config.watchdog ==
"on") ?
true :
false;
150 else if (level == 21)
154 else if (level == 22)
158 else if (level == 23)
162 else if (level == 24)