99 constexpr
char LOGNAME[] =
"omni exploration";
101 int main(
int argc,
char** argv)
111 arma::arma_rng::set_seed_random();
118 const auto map_frame_id = pnh.
param<std::string>(
"map_frame_id",
"map");
119 const auto base_frame_id = pnh.
param<std::string>(
"base_frame_id",
"base_link");
122 const double frequency = pnh.
param(
"frequency", 10.0);
124 const double val_dt = pnh.
param(
"val_dt", 0.1);
125 const double val_horizon = pnh.
param(
"val_horizon", 0.5);
127 const double max_vel_x = pnh.
param(
"max_vel_x", 1.0);
128 const double max_vel_y = pnh.
param(
"max_vel_y", 1.0);
129 const double max_rot_vel = pnh.
param(
"max_rot_vel", 1.0);
131 const double min_vel_x = pnh.
param(
"min_vel_x", -1.0);
132 const double min_vel_y = pnh.
param(
"min_vel_y", -1.0);
133 const double min_rot_vel = pnh.
param(
"min_rot_vel", -1.0);
135 const double acc_lim_x = pnh.
param(
"acc_lim_x", 1.0);
136 const double acc_lim_y = pnh.
param(
"acc_lim_y", 1.0);
137 const double acc_lim_th = pnh.
param(
"acc_lim_th", 1.0);
139 const vec umin = { min_vel_x, min_vel_y, min_rot_vel };
140 const vec umax = { max_vel_x, max_vel_y, max_rot_vel };
143 const double boundary_radius = pnh.
param(
"boundary_radius", 0.7);
144 const double search_radius = pnh.
param(
"search_radius", 1.0);
145 const double obstacle_threshold = pnh.
param(
"obstacle_threshold", 0.2);
146 const double occupied_threshold = pnh.
param(
"occupied_threshold", 0.8);
149 const double ec_dt = pnh.
param(
"ec_dt", 0.1);
150 const double ec_horizon = pnh.
param(
"ec_horizon", 2.0);
151 const double target_resolution = pnh.
param(
"target_resolution", 0.1);
152 const double expl_weight = pnh.
param(
"expl_weight", 1.0);
153 const unsigned int num_basis = pnh.
param(
"num_basis", 10);
154 const unsigned int buffer_size = pnh.
param(
"buffer_size", 1e6);
155 const unsigned int batch_size = pnh.
param(
"batch_size", 100);
157 std::vector<double> control_weights = { 1.0, 1.0, 1.0 };
158 pnh.
getParam(
"control_weights", control_weights);
161 mat Rinv(3, 3, arma::fill::zeros);
162 Rinv(0, 0) = 1.0 / control_weights.at(0);
163 Rinv(1, 1) = 1.0 / control_weights.at(1);
164 Rinv(2, 2) = 1.0 / control_weights.at(2);
167 const double dwa_dt = pnh.
param(
"dwa_dt", 0.1);
168 const double dwa_horizon = pnh.
param(
"dwa_horizon", 1.0);
169 const double acc_dt = pnh.
param(
"acc_dt", 0.2);
170 const unsigned int vx_samples = pnh.
param(
"vx_samples", 3);
171 const unsigned int vy_samples = pnh.
param(
"vy_samples", 8);
172 const unsigned int vth_samples = pnh.
param(
"vth_samples", 5);
174 if (dwa_horizon > ec_horizon)
177 LOGNAME,
"Dynamic window horizon is greater than the ergodic control horizon");
186 const auto num_targets =
static_cast<unsigned int>(means.
size());
189 for (
unsigned int i = 0; i < num_targets; i++)
191 gaussians.at(i) = { { means[i][0], means[i][1] }, { sigmas[i][0], sigmas[i][1] } };
194 const Target target(gaussians);
197 const Collision collision(boundary_radius, search_radius, obstacle_threshold,
200 const ErgodicControl ergodic_control(omni, collision, ec_dt, ec_horizon,
201 target_resolution, expl_weight, num_basis,
202 buffer_size, batch_size, Rinv, umin, umax);
204 const DynamicWindow dwa(collision, dwa_dt, dwa_horizon, acc_dt, acc_lim_x, acc_lim_y,
205 acc_lim_th, max_vel_x, min_vel_x, max_vel_y, min_vel_y,
206 max_rot_vel, min_rot_vel, vx_samples, vy_samples, vth_samples);
211 exploration.
control(target, map_frame_id, base_frame_id, frequency, val_dt, val_horizon);