Skip to content

Commit

Permalink
Merge pull request #127 from RoboTeamTwente/Update/rem_version_7
Browse files Browse the repository at this point in the history
Update for new rem version 7
  • Loading branch information
JWillegers authored Jun 6, 2024
2 parents 436658a + aba4686 commit 7be4c91
Show file tree
Hide file tree
Showing 121 changed files with 7,520 additions and 5,793 deletions.
7 changes: 2 additions & 5 deletions docs/Robot.md
Original file line number Diff line number Diff line change
Expand Up @@ -15,11 +15,11 @@ The enum Team in [team.hpp](https://github.com/RoboTeamTwente/roboteam_ai/blob/d

`vel` -> Current velocity of the robot

`angle` -> Current angle of the robot
`yaw` -> Current yaw of the robot

`distanceToBall` -> Distance from the robot to the ball

`angleDiffToBall` -> Angle offset between the kicker and the ball.
`angleDiffToBall` -> Angle offset between the yaw of the kicker and the vector from robot center to ball

`angularVelocity` -> Angular velocity of the robot.

Expand All @@ -33,9 +33,6 @@ The enum Team in [team.hpp](https://github.com/RoboTeamTwente/roboteam_ai/blob/d

`DribblerSeesBall` -> True if the dribbler picks up the ball, false if not.

`ballPos` -> Position of the ball (if seesBall == true)


## Functions ##

### Trivial getters and setters, therefore will **not** be covered ##
Expand Down
6 changes: 3 additions & 3 deletions roboteam_ai/include/roboteam_ai/control/ControlModule.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
#include <mutex>
#include <roboteam_utils/RobotCommands.hpp>

#include "control/AnglePID.h"
#include "control/YawPID.h"
#include "world/views/RobotView.hpp"

namespace rtt::ai::control {
Expand All @@ -18,8 +18,8 @@ namespace rtt::ai::control {
*/
class ControlModule {
protected:
static inline std::vector<rtt::RobotCommand> robotCommands; /**< Vector of all robot commands */
static inline std::map<unsigned int, AnglePID> simulatorAnglePIDmap; /**< Angle controller for each robot */
static inline std::vector<rtt::RobotCommand> robotCommands; /**< Vector of all robot commands */
static inline std::map<unsigned int, YawPID> simulatorYawPIDmap; /**< Yaw controller for each robot */

/**
* @brief Applies constraints to the internal robot command
Expand Down
1 change: 0 additions & 1 deletion roboteam_ai/include/roboteam_ai/control/ControlUtils.h
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,6 @@
#include "utilities/Constants.h"

using Vector2 = rtt::Vector2;
using Angle = rtt::Angle;

namespace rtt::ai::control {

Expand Down
Original file line number Diff line number Diff line change
@@ -1,13 +1,13 @@
#ifndef RTT_ANGLEPID_H
#define RTT_ANGLEPID_H
#ifndef RTT_YAWPID_H
#define RTT_YAWPID_H

#include "roboteam_utils/Angle.h"
#include "roboteam_utils/pid.h"
namespace rtt {
/**
* @brief Class that controls the angle with a PID
* @brief Class that controls the yaw with a PID
*/
class AnglePID {
class YawPID {
private:
double P; /**< Proportional part of the controller */
double I; /**< Integral part of the controller */
Expand All @@ -20,23 +20,23 @@ class AnglePID {

public:
/**
* @brief Constructor of the AnglePID class
* @brief Constructor of the YawPID class
* @param P Proportional part of the controller
* @param I Integral part of the controller
* @param D Derivative part of the controller
* @param max_ang_vel Absolute maximum allowed angular velocity
* @param dt Time difference since previous tick
*/
AnglePID(double P, double I, double D, double max_ang_vel, double dt) : P{P}, I{I}, D{D}, min{-max_ang_vel}, max{max_ang_vel}, previous_error{0.0}, integral{0.0}, dt{dt} {}
YawPID(double P, double I, double D, double max_ang_vel, double dt) : P{P}, I{I}, D{D}, min{-max_ang_vel}, max{max_ang_vel}, previous_error{0.0}, integral{0.0}, dt{dt} {}

/**
* @brief Retrieves the angular velocity calculated by the controller
* @param target_angle Angle the robot needs to be at
* @param current_angle Current angle of the robot
* @param target_yaw Yaw the robot needs to be at
* @param current_yaw Current yaw of the robot
* @return Target angular velocity
*/
double getOutput(Angle target_angle, Angle current_angle);
double getOutput(Angle target_yaw, Angle current_yaw);
};
} // namespace rtt

#endif // RTT_ANGLEPID_H
#endif // RTT_YAWPID_H
16 changes: 8 additions & 8 deletions roboteam_ai/include/roboteam_ai/stp/StpInfo.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,11 +40,11 @@ struct StpInfo {
double getKickChipVelocity() const { return kickChipVelocity; }
void setKickChipVelocity(double kickChipVelocity) { this->kickChipVelocity = kickChipVelocity; }

Angle getAngle() const { return angle; }
void setAngle(double angle) { this->angle = Angle(angle); }
Angle getYaw() const { return yaw; }
void setYaw(double yaw) { this->yaw = Angle(yaw); }

int getDribblerSpeed() const { return dribblerSpeed; }
void setDribblerSpeed(int dribblerSpeed) { this->dribblerSpeed = dribblerSpeed; }
bool getDribblerOn() const { return dribblerOn; }
void setDribblerOn(bool dribblerOn) { this->dribblerOn = dribblerOn; }

ShotType getShotType() const { return shotType; }
void setShotType(ShotType shotType) { this->shotType = shotType; }
Expand Down Expand Up @@ -152,14 +152,14 @@ struct StpInfo {
ShotType shotType{};

/**
* Reference angle of the robot
* Reference yaw of the robot
*/
Angle angle = Angle(0.0);
Angle yaw = Angle(0.0);

/**
* Speed of the dribbler in %
* Whether the dribbler should be on
*/
int dribblerSpeed = 0;
bool dribblerOn;

/**
* Set the shot to be a kick or chip
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,8 +37,8 @@ constexpr double ENEMY_CLOSE_TO_BALL_DISTANCE = 1.0; /**< Distanc

/// RobotCommand limits
constexpr double MAX_DRIBBLER_CMD = 1; /**< Maximum allowed dribbler velocity that can be send to the robot */
// Angle increment per tick
constexpr double ANGLE_RATE = 0.2 * M_PI; /**< Maximum allowed angular velocity that can be send to the robot */
// Yaw increment per tick
constexpr double YAW_RATE = 0.2 * M_PI; /**< Maximum allowed angular velocity that can be send to the robot */
constexpr double MAX_VEL_WHEN_HAS_BALL = 3.0; /**< Maximum allowed velocity that can be send to the robot when that robot has the ball */

/// GoToPos Constants
Expand Down
6 changes: 3 additions & 3 deletions roboteam_ai/include/roboteam_ai/stp/tactics/KeeperBlockBall.h
Original file line number Diff line number Diff line change
Expand Up @@ -83,12 +83,12 @@ class KeeperBlockBall : public Tactic {
static std::pair<Vector2, bool> calculateTargetPosition(const StpInfo info) noexcept;

/**
* @brief Calculates the angle the robot should have
* @brief Calculates the yaw the robot should have
* @param ball the ball for which the keeper should defend
* @param targetKeeperPosition the target position the keeper should have
* @return the angle the robot should have
* @return the yaw the robot should have
*/
static Angle calculateTargetAngle(const world::view::BallView &ball, const Vector2 &targetKeeperPosition);
static Angle calculateYaw(const world::view::BallView &ball, const Vector2 &targetKeeperPosition);
};
} // namespace rtt::ai::stp::tactic

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ class ChipAtPos : public Tactic {
* @brief Should this tactic be reset (go back to the first skill of this tactic)
* @param info StpInfo can be used to check some data
* @return true if tactic should reset, false if execution should continue
* Returns true when the robot angle is not within its error margin
* Returns true when the robot yaw is not within its error margin
*/
bool shouldTacticReset(const StpInfo &info) noexcept override;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ class DriveWithBall : public Tactic {

/**
* @brief Should this tactic be reset (go back to the first skill of this tactic)
* Should reset if the angle the robot is at is no longer correct
* Should reset if the yaw the robot is at is no longer correct
* @param info StpInfo can be used to check some data
* @return true if tactic should reset, false if execution should continue
*/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ class InstantKick : public Tactic {

/**
* @brief Should this tactic be reset (go back to the first skill of this tactic)
* Returns true when the robot angle is outside some error margin
* Returns true when the robot yaw is outside some error margin
* @param info StpInfo can be used to check some data
* @return true if tactic should reset, false if execution should continue
*/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ class OrbitKick : public Tactic {

/**
* @brief Should this tactic be reset (go back to the first skill of this tactic)
* Returns true when the robot angle is outside some error margin
* Returns true when the robot yaw is outside some error margin
* @param info StpInfo can be used to check some data
* @return true if tactic should reset, false if execution should continue
*/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ class Receive : public Tactic {
const char *getName() override;

/**
* @brief Calculates the angle the robot needs to have using the ball position
* @brief Calculates the yaw the robot needs to have using the ball position
* @param robot
* @param ball
* @return Angle the robot should take
Expand Down
2 changes: 1 addition & 1 deletion roboteam_ai/include/roboteam_ai/stp/tactics/passive/Halt.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@

namespace rtt::ai::stp::tactic {
/**
* @brief Class that defines the halt tactic. This tactic is used for halting, it rotates the robot to angle 0
* @brief Class that defines the halt tactic. This tactic is used for halting, it rotates the robot to yaw 0
* It cannot fail and reset. It's not an
* end tactic, therefore it can succeed.
*/
Expand Down
4 changes: 2 additions & 2 deletions roboteam_ai/include/roboteam_ai/utilities/Constants.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,8 +44,8 @@ class Constants {

/// ROBOT COMMANDS ///
static double MAX_VEL_CMD(); /**< The maximum allowed velocity of the robot */
static double MIN_ANGLE(); /**< The minimum angle the robot can have */
static double MAX_ANGLE(); /**< The maximum angle the robot can have */
static double MIN_YAW(); /**< The minimum yaw the robot can have */
static double MAX_YAW(); /**< The maximum yaw the robot can have */
static double MAX_ANGULAR_VELOCITY(); /**< The maximum angular velocity of the robot */
static double MAX_ACC(); /**< Maximum acceleration of the robot */

Expand Down
8 changes: 4 additions & 4 deletions roboteam_ai/include/roboteam_ai/utilities/IOManager.h
Original file line number Diff line number Diff line change
Expand Up @@ -53,10 +53,10 @@ class IOManager {
rtt::ai::Pause* pause; /**< Pauses the robots when needed */

/**
* @brief Adds the camera angle from world to the robot commands, so the robot can use it for its angle control
* @param robotCommands the robot commands in which the camera angle needs to be added
* @brief Adds the camera yaw from world to the robot commands, so the robot can use it for its yaw control
* @param robotCommands the robot commands in which the camera yaw needs to be added
*/
void addCameraAngleToRobotCommands(rtt::RobotCommands& robotCommands);
void addCameraYawToRobotCommands(rtt::RobotCommands& robotCommands);
/**
* @brief Publishes the robot commands on the given team's socket.
* @param robotCommands Commands that need to be published
Expand All @@ -67,7 +67,7 @@ class IOManager {

public:
/**
* @brief Publishes all robot commands with the robot angles from world
* @brief Publishes all robot commands with the robot yaw from world
* @param robotCommands Commands that need to be published
*/
void publishAllRobotCommands(rtt::RobotCommands& robotCommands);
Expand Down
27 changes: 10 additions & 17 deletions roboteam_ai/include/roboteam_ai/world/Robot.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ class Robot {

Vector2 pos; /**< Position of the robot */
Vector2 vel; /**< Velocity of the robot */
Angle angle; /**< Angle of the robot */
Angle yaw; /**< Yaw of the robot */

double distanceToBall; /**< Distance from the robot to the ball */
double angleDiffToBall; /**< Angle of the robot relative to the ball */
Expand All @@ -43,7 +43,6 @@ class Robot {
bool workingBallSensor{}; /**< Indicates whether the robot has a working ball sensor */

bool ballSensorSeesBall{}; /**< Indicates whether the ball sensor sees the ball */
float ballPos{}; /**< The position of the ball */
bool dribblerSeesBall{}; /**< Indicates whether the dribbler sees the ball */
bool robotHasBall{}; /**< Indicates whether the robot has the ball */

Expand All @@ -63,10 +62,10 @@ class Robot {
void updateHasBallMap(std::optional<view::BallView> &ball);

/**
* @brief Set the angle of the robot according to the given angle
* @param angle The angle to which the robot angle should be set to
* @brief Sets the robot's yaw to the specified yaw
* @param yaw The desired yaw for the robot
*/
void setAngle(const Angle &angle) noexcept;
void setYaw(const Angle &yaw) noexcept;

/**
* @brief Set the batteryLow boolean
Expand All @@ -87,7 +86,7 @@ class Robot {
void setDistanceToBall(double distanceToBall) noexcept;

/**
* @brief Set the angle difference to the ball
* @brief Set the yaw difference to the ball
* @param _angleDiffToBall The Angle of the robot relative to the ball
*/
void setAngleDiffToBall(double _angleDiffToBall) noexcept;
Expand All @@ -110,12 +109,6 @@ class Robot {
*/
void setHasBall(bool _hasBall) noexcept;

/**
* @brief Set the ball position according to the ball sensor
* @param _ballPos The position of the ball according to the ball sensor
*/
void setBallPosBallSensor(float _ballPos) noexcept;

public:
/**
* @brief Get the ID of the robot
Expand All @@ -142,10 +135,10 @@ class Robot {
[[nodiscard]] const Vector2 &getVel() const noexcept;

/**
* @brief Get the angle of the robot
* @return The angle of the robot
* @brief Get the yaw of the robot
* @return The yaw of the robot
*/
[[nodiscard]] const Angle &getAngle() const noexcept;
[[nodiscard]] const Angle &getYaw() const noexcept;

/**
* @brief Get the angular velocity of the robot
Expand Down Expand Up @@ -184,8 +177,8 @@ class Robot {
[[nodiscard]] double getDistanceToBall() const noexcept;

/**
* @brief Get the angle of the robot relative to the ball
* @return The angle of the robot relative to the ball
* @brief Get the yaw of the robot relative to the ball
* @return The yaw of the robot relative to the ball
*/
[[nodiscard]] double getAngleDiffToBall() const noexcept;

Expand Down
Loading

0 comments on commit 7be4c91

Please sign in to comment.