Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

removed all the using namespaces #339

Merged
merged 5 commits into from
Nov 8, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 3 additions & 3 deletions src/autonomous/AutonomousTask.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ void AutonomousTask::navigate() {
SLOW_DRIVE_THRESHOLD, DONE_THRESHOLD,
CLOSE_TO_TARGET_DUR_VAL);

DiffDriveKinematics diffDriveKinematics(Constants::EFF_WHEEL_BASE);
kinematics::DiffDriveKinematics diffDriveKinematics(Constants::EFF_WHEEL_BASE);

auto sleepUntil = std::chrono::steady_clock().now();
while (!cmd.isDone()) {
Expand All @@ -50,8 +50,8 @@ void AutonomousTask::navigate() {
cmd.setState(latestPos, robot::types::dataclock::now());
commands::command_t output = cmd.getOutput();
auto scaledVels = diffDriveKinematics.ensureWithinWheelSpeedLimit(
DiffDriveKinematics::PreferredVelPreservation::PreferThetaVel, output.xVel,
output.thetaVel, Constants::MAX_WHEEL_VEL);
kinematics::DiffDriveKinematics::PreferredVelPreservation::PreferThetaVel,
output.xVel, output.thetaVel, Constants::MAX_WHEEL_VEL);
navtypes::point_t relTarget = util::toTransform(latestPos) * _waypoint_coords;
LOG_F(INFO, "Relative Target: (%lf, %lf)", relTarget(0), relTarget(1));
LOG_F(INFO, "thetaVel: %lf", scaledVels(2));
Expand Down
6 changes: 3 additions & 3 deletions src/control_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ using namespace std::chrono_literals;

namespace robot {
namespace {
jointpos_t commandedWristPos{0, 0};
kinematics::jointpos_t commandedWristPos{0, 0};
std::mutex wristPosMutex;

void setJointMotorPower(robot::types::jointid_t joint, double power);
Expand Down Expand Up @@ -57,7 +57,7 @@ double setCmdVel(double dtheta, double dx) {
}
}

wheelvel_t wheelVels = driveKinematics().robotVelToWheelVel(dx, dtheta);
kinematics::wheelvel_t wheelVels = driveKinematics().robotVelToWheelVel(dx, dtheta);
double lPWM = wheelVels.lVel / Constants::MAX_WHEEL_VEL;
double rPWM = wheelVels.rVel / Constants::MAX_WHEEL_VEL;
double maxAbsPWM = std::max(std::abs(lPWM), std::abs(rPWM));
Expand Down Expand Up @@ -92,7 +92,7 @@ double setTankCmdVel(double left, double right) {
if (!Globals::swerveController.checkWheelRotation(DriveMode::Normal, curr_wheel_rots))
return 0;

wheelvel_t wheelVels = {left, right};
kinematics::wheelvel_t wheelVels = {left, right};
double lPWM = wheelVels.lVel / Constants::MAX_WHEEL_VEL;
double rPWM = wheelVels.rVel / Constants::MAX_WHEEL_VEL;
double maxAbsPWM = std::max(std::abs(lPWM), std::abs(rPWM));
Expand Down
3 changes: 1 addition & 2 deletions src/kinematics/SwerveDriveKinematics.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@
#include "../navtypes.h"

namespace kinematics {
using namespace navtypes;

/**
* Represents robot wheel velocities in robot reference frame,
Expand Down Expand Up @@ -61,7 +60,7 @@ class SwerveDriveKinematics {
* robot's reference frame.
* @return the robot's translational and angular velocity in the robot's reference frame.
*/
pose_t wheelVelToRobotVel(swervewheelvel_t wheelVel) const;
navtypes::pose_t wheelVelToRobotVel(swervewheelvel_t wheelVel) const;

/**
* Calculate the pose update in the local reference frame given the velocities of the
Expand Down
4 changes: 2 additions & 2 deletions src/world_interface/simulator_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -249,10 +249,10 @@ void initSimServer(net::websocket::SingleClientWSServer& ws) {
namespace robot {

namespace {
DiffDriveKinematics drive_kinematics(Constants::EFF_WHEEL_BASE);
kinematics::DiffDriveKinematics drive_kinematics(Constants::EFF_WHEEL_BASE);
} // namespace

const DiffDriveKinematics& driveKinematics() {
const kinematics::DiffDriveKinematics& driveKinematics() {
return drive_kinematics;
}

Expand Down
1 change: 0 additions & 1 deletion src/world_interface/world_interface.h
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,6 @@
#include <optional>
#include <unordered_set>

using namespace kinematics;
// forward declare cam::CameraParams instead of including it
// we do this to avoid unnecessarily including OpenCV in all build targets
namespace cam {
Expand Down