|
| 1 | +// |
| 2 | +// Created by yezi on 24-1-26. |
| 3 | +// |
| 4 | + |
| 5 | +#pragma once |
| 6 | + |
| 7 | +#include <tf2_geometry_msgs/tf2_geometry_msgs.h> |
| 8 | +#include <tf/transform_datatypes.h> |
| 9 | + |
| 10 | +class TargetKinematicsBase |
| 11 | +{ |
| 12 | +public: |
| 13 | + virtual ~TargetKinematicsBase() = default; |
| 14 | + virtual geometry_msgs::Point position(double time) = 0; |
| 15 | + virtual geometry_msgs::Vector3 velocity(double time) = 0; |
| 16 | + virtual geometry_msgs::Vector3 acceleration(double time) = 0; |
| 17 | +}; |
| 18 | + |
| 19 | +class NormalTargetKinematics : public TargetKinematicsBase |
| 20 | +{ |
| 21 | +public: |
| 22 | + NormalTargetKinematics(geometry_msgs::Point pos, geometry_msgs::Vector3 vel, double yaw, double v_yaw, double r) |
| 23 | + { |
| 24 | + pos_ = pos; |
| 25 | + vel_ = vel; |
| 26 | + yaw_ = yaw; |
| 27 | + v_yaw_ = v_yaw; |
| 28 | + r_ = r; |
| 29 | + } |
| 30 | + |
| 31 | +protected: |
| 32 | + geometry_msgs::Point pos_; |
| 33 | + geometry_msgs::Vector3 vel_; |
| 34 | + double yaw_; |
| 35 | + double v_yaw_; |
| 36 | + double r_; |
| 37 | +}; |
| 38 | + |
| 39 | +class TrackedTargetKinematics : public NormalTargetKinematics |
| 40 | +{ |
| 41 | +public: |
| 42 | + TrackedTargetKinematics(geometry_msgs::Point pos, geometry_msgs::Vector3 vel, double yaw, double v_yaw, double r) |
| 43 | + : NormalTargetKinematics(pos, vel, yaw, v_yaw, r) |
| 44 | + { |
| 45 | + } |
| 46 | + geometry_msgs::Point position(double time) override |
| 47 | + { |
| 48 | + geometry_msgs::Point target_pos; |
| 49 | + target_pos.x = pos_.x + vel_.x * time - r_ * cos(yaw_ + v_yaw_ * time); |
| 50 | + target_pos.y = pos_.y + vel_.y * time - r_ * sin(yaw_ + v_yaw_ * time); |
| 51 | + target_pos.z = pos_.z + vel_.z * time; |
| 52 | + return target_pos; |
| 53 | + } |
| 54 | + geometry_msgs::Vector3 velocity(double time) override |
| 55 | + { |
| 56 | + geometry_msgs::Vector3 target_vel; |
| 57 | + target_vel.x = vel_.x + v_yaw_ * r_ * sin(yaw_ + v_yaw_ * time); |
| 58 | + target_vel.y = vel_.y - v_yaw_ * r_ * cos(yaw_ + v_yaw_ * time); |
| 59 | + return target_vel; |
| 60 | + } |
| 61 | + geometry_msgs::Vector3 acceleration(double time) override |
| 62 | + { |
| 63 | + geometry_msgs::Vector3 target_accel; |
| 64 | + target_accel.x = pow(v_yaw_, 2) * r_ * cos(yaw_ + v_yaw_ * time); |
| 65 | + target_accel.y = pow(v_yaw_, 2) * r_ * sin(yaw_ + v_yaw_ * time); |
| 66 | + return target_accel; |
| 67 | + } |
| 68 | +}; |
| 69 | + |
| 70 | +class UntrackedTargetKinematic : public NormalTargetKinematics |
| 71 | +{ |
| 72 | +public: |
| 73 | + UntrackedTargetKinematic(geometry_msgs::Point pos, geometry_msgs::Vector3 vel, double yaw, double v_yaw, double r) |
| 74 | + : NormalTargetKinematics(pos, vel, yaw, v_yaw, r) |
| 75 | + { |
| 76 | + } |
| 77 | + geometry_msgs::Point position(double time) override |
| 78 | + { |
| 79 | + geometry_msgs::Point target_pos; |
| 80 | + double target_center_pos[2]; |
| 81 | + target_center_pos[0] = pos_.x + vel_.x * time; |
| 82 | + target_center_pos[1] = pos_.y + vel_.y * time; |
| 83 | + target_pos.x = target_center_pos[0] - r_ * cos(atan2(target_center_pos[1], target_center_pos[0])); |
| 84 | + target_pos.y = target_center_pos[1] - r_ * sin(atan2(target_center_pos[1], target_center_pos[0])); |
| 85 | + target_pos.z = pos_.z + vel_.z * time; |
| 86 | + return target_pos; |
| 87 | + } |
| 88 | + geometry_msgs::Vector3 velocity(double time) override |
| 89 | + { |
| 90 | + geometry_msgs::Vector3 target_vel; |
| 91 | + return target_vel; |
| 92 | + } |
| 93 | + geometry_msgs::Vector3 acceleration(double time) override |
| 94 | + { |
| 95 | + geometry_msgs::Vector3 target_accel; |
| 96 | + return target_accel; |
| 97 | + } |
| 98 | +}; |
| 99 | + |
| 100 | +class WindmillKinematics : public TargetKinematicsBase |
| 101 | +{ |
| 102 | +public: |
| 103 | + WindmillKinematics(double theta, double theta_dot, double radius, geometry_msgs::TransformStamped windmill2odom) |
| 104 | + { |
| 105 | + theta_ = theta; |
| 106 | + theta_dot_ = theta_dot; |
| 107 | + radius_ = radius; |
| 108 | + windmill2odom_ = windmill2odom; |
| 109 | + } |
| 110 | + geometry_msgs::Point position(double time) override |
| 111 | + { |
| 112 | + geometry_msgs::Point target_pos; |
| 113 | + target_pos.x = 0.; |
| 114 | + target_pos.y = -radius_ * sin(theta_ + theta_dot_ * time); |
| 115 | + target_pos.z = radius_ * cos(theta_ + theta_dot_ * time); |
| 116 | + tf2::doTransform(target_pos, target_pos, windmill2odom_); |
| 117 | + return target_pos; |
| 118 | + } |
| 119 | + geometry_msgs::Vector3 velocity(double time) override |
| 120 | + { |
| 121 | + geometry_msgs::Vector3 target_vel; |
| 122 | + target_vel.x = 0.; |
| 123 | + target_vel.y = -theta_dot_ * radius_ * cos(theta_ + theta_dot_ * time); |
| 124 | + target_vel.z = -theta_dot_ * radius_ * sin(theta_ + theta_dot_ * time); |
| 125 | + tf2::doTransform(target_vel, target_vel, windmill2odom_); |
| 126 | + return target_vel; |
| 127 | + } |
| 128 | + geometry_msgs::Vector3 acceleration(double time) override |
| 129 | + { |
| 130 | + geometry_msgs::Vector3 target_accel; |
| 131 | + target_accel.x = 0.; |
| 132 | + target_accel.y = pow(theta_dot_, 2) * radius_ * sin(theta_ + theta_dot_ * time); |
| 133 | + target_accel.z = -pow(theta_dot_, 2) * radius_ * cos(theta_ + theta_dot_ * time); |
| 134 | + tf2::doTransform(target_accel, target_accel, windmill2odom_); |
| 135 | + return target_accel; |
| 136 | + } |
| 137 | + |
| 138 | +private: |
| 139 | + double theta_; |
| 140 | + double theta_dot_; |
| 141 | + double radius_; |
| 142 | + geometry_msgs::TransformStamped windmill2odom_; |
| 143 | +}; |
0 commit comments