Added dwm rotate

This commit is contained in:
2025-02-26 16:29:20 +01:00
parent 74c5bc77cc
commit 4b30d10783
3 changed files with 81 additions and 5 deletions

View File

@ -0,0 +1,66 @@
#pragma once
#include "handlers/dwm_core.hpp"
#include "glm/gtx/norm.hpp"
#include "glm/gtx/rotate_vector.hpp"
#include "glm/gtx/vector_angle.hpp"
#include <glm/gtc/constants.hpp>
namespace mg {
template <>
inline bool DWM<MgNavigationServer::Rotate>::target_check() {
const double a = glm::abs(theta - target_ornt);
const double b = (a > glm::pi<double>()) ? glm::two_pi<double>() - a : a;
return b > goal->tolerance;
}
template <>
inline void DWM<MgNavigationServer::Rotate>::target_init() {
target_ornt = goal->angle;
}
template <>
inline bool DWM<MgNavigationServer::Rotate>::condition_check() {
return false;
}
template <>
inline double DWM<MgNavigationServer::Rotate>::calc_score(int vl, int vr) {
constexpr double delta = 0.5;
const auto [v, w] = to_vel(step * vl, step * vr);
const double n_theta = theta + w * delta;
double dist_old = glm::abs(target_ornt - theta);
double dist_new = glm::abs(target_ornt - n_theta);
dist_old = (dist_old > glm::pi<double>()) ? glm::two_pi<double>() - dist_old : dist_old;
dist_new = (dist_new > glm::pi<double>()) ? glm::two_pi<double>() - dist_new : dist_new;
const double score = goal->ornt_mult * (dist_old - dist_new);
return score;
}
template <>
inline void DWM<MgNavigationServer::Rotate>::populate_candidates(std::vector<int>& vl,
std::vector<int>& vr,
int dimx,
int) {
vl.clear();
vr.clear();
for (int i = -dimx / 2; i <= dimx / 2; i++) {
auto [v, w] = to_vel(step * (cvl + i), step * (cvr + i));
if (step * abs(cvl - i) <= goal->max_wheel_speed && step * abs(cvr + i) <= goal->max_wheel_speed
&& glm::abs(w) < goal->max_angular) {
vl.push_back(cvl - i);
vr.push_back(cvr + i);
}
}
}
}

View File

@ -8,6 +8,7 @@
#include "mg_msgs/action/move_point.hpp"
#include "mg_msgs/action/move_straight.hpp"
#include "mg_msgs/action/look_at.hpp"
#include "mg_msgs/action/rotate.hpp"
#include "geometry_msgs/msg/twist_stamped.hpp"
#include "geometry_msgs/msg/transform_stamped.hpp"
@ -26,12 +27,14 @@ namespace mg {
using MovePoint = mg_msgs::action::MovePoint;
using MoveStraight = mg_msgs::action::MoveStraight;
using LookAt = mg_msgs::action::LookAt;
using Rotate = mg_msgs::action::Rotate;
rclcpp::Publisher<Geometry::TwistStamped>::SharedPtr pub_twist;
rclcpp_action::Server<LookAt>::SharedPtr sv_look_at;
rclcpp_action::Server<MovePoint>::SharedPtr sv_move_point;
rclcpp_action::Server<MoveStraight>::SharedPtr sv_move_straight;
rclcpp_action::Server<LookAt>::SharedPtr sv_look_at;
rclcpp_action::Server<Rotate>::SharedPtr sv_rotate;
rclcpp::Subscription<Geometry::TransformStamped>::SharedPtr tf2_subscription_;
tf2_ros::Buffer::SharedPtr tf2_buffer;

View File

@ -60,6 +60,13 @@ namespace mg {
std::bind(&MgNavigationServer::handle_cancel<MovePoint>, this, _1, "MovePoint"),
std::bind(&MgNavigationServer::handle_accepted<MovePoint>, this, _1, "MovePoint"));
sv_move_straight = rclcpp_action::create_server<MoveStraight>(
this,
"MoveStraight",
std::bind(&MgNavigationServer::handle_goal<MoveStraight>, this, _1, _2, "MoveStraight"),
std::bind(&MgNavigationServer::handle_cancel<MoveStraight>, this, _1, "MoveStraight"),
std::bind(&MgNavigationServer::handle_accepted<MoveStraight>, this, _1, "MoveStraight"));
sv_look_at = rclcpp_action::create_server<LookAt>(
this,
"LookAt",
@ -67,12 +74,12 @@ namespace mg {
std::bind(&MgNavigationServer::handle_cancel<LookAt>, this, _1, "LookAt"),
std::bind(&MgNavigationServer::handle_accepted<LookAt>, this, _1, "LookAt"));
sv_move_straight = rclcpp_action::create_server<MoveStraight>(
sv_rotate = rclcpp_action::create_server<Rotate>(
this,
"MoveStraight",
std::bind(&MgNavigationServer::handle_goal<MoveStraight>, this, _1, _2, "MoveStraight"),
std::bind(&MgNavigationServer::handle_cancel<MoveStraight>, this, _1, "MoveStraight"),
std::bind(&MgNavigationServer::handle_accepted<MoveStraight>, this, _1, "MoveStraight"));
std::bind(&MgNavigationServer::handle_goal<Rotate>, this, _1, _2, "MoveStraight"),
std::bind(&MgNavigationServer::handle_cancel<Rotate>, this, _1, "MoveStraight"),
std::bind(&MgNavigationServer::handle_accepted<Rotate>, this, _1, "MoveStraight"));
}
};