Added collision avoidance to MoveGlobal routine

This commit is contained in:
2025-05-05 01:34:53 +02:00
parent a160af8de3
commit ccfd1189c2
30 changed files with 792 additions and 33 deletions

View File

@ -15,6 +15,7 @@ namespace mg {
template <>
inline void DWA<MgNavigationServer::MovePoint>::target_update() {
target_pos = glm::dvec2(goal->x, goal->y);
dimy = 8;
}
template <>
@ -25,7 +26,7 @@ namespace mg {
template <>
inline double DWA<MgNavigationServer::MovePoint>::calc_score(int vl, int vr) {
auto [v, w] = to_vel(step * vl, step * vr);
const double delta = 0.5;
const double delta = 0.3;
glm::dvec2 n_pos;
double n_theta = NAN;
double score = 0;