Skip to content

Commit

Permalink
pretty much working + squash me
Browse files Browse the repository at this point in the history
  • Loading branch information
huttongrabiel committed Jan 12, 2024
1 parent 0729d15 commit 4f45243
Show file tree
Hide file tree
Showing 2 changed files with 12 additions and 8 deletions.
6 changes: 4 additions & 2 deletions src/autonomous/AutonomousTask.cpp
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
#include "AutonomousTask.h"

#include "../Constants.h"
#include "../Globals.h"
#include "../commands/DriveToWaypointCommand.h"
#include "../world_interface/world_interface.h"

Expand Down Expand Up @@ -31,6 +30,8 @@ void AutonomousTask::navigate() {
commands::DriveToWaypointCommand cmd(_waypoint_coords, THETA_KP, DRIVE_VEL, SLOW_DRIVE_VEL,
DONE_THRESHOLD, CLOSE_TO_TARGET_DUR_VAL);

DiffDriveKinematics diffDriveKinematics(Constants::EFF_WHEEL_BASE);

auto sleepUntil = std::chrono::steady_clock().now();
while (!cmd.isDone()) {
auto latestGPS = robot::readGPS();
Expand All @@ -41,7 +42,8 @@ void AutonomousTask::navigate() {
navtypes::pose_t latestPos(gpsData.x(), gpsData.y(), latestHeading.getData());
cmd.setState(latestPos, robot::types::dataclock::now());
commands::command_t output = cmd.getOutput();
robot::setCmdVel(output.thetaVel, output.xVel);
auto scaledVels = diffDriveKinematics.ensureWithinWheelSpeedLimit(DiffDriveKinematics::PreferredVelPreservation::PreferThetaVel, output.xVel, output.thetaVel, Constants::MAX_WHEEL_VEL);
robot::setCmdVel(scaledVels(2), scaledVels(0));
}

std::unique_lock autonomousTaskLock(_autonomous_task_mutex);
Expand Down
14 changes: 8 additions & 6 deletions src/network/MissionControlProtocol.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -227,15 +227,16 @@ void MissionControlProtocol::sendRoverPos() {
static bool validateWaypointNavRequest(const json& j) {
return util::validateKey(j, "latitude", val_t::string) &&
util::validateKey(j, "longitude", val_t::string);
util::validateKey(j, "isApproximate", val_t::boolean) &&
util::validateKey(j, "isGate", val_t::boolean);
// FIXME: Add these back in
// util::validateKey(j, "isApproximate", val_t::boolean) &&
// util::validateKey(j, "isGate", val_t::boolean);
}

void MissionControlProtocol::handleWaypointNavRequest(const json& j) {
std::string latitude = j["latitude"];
std::string longitude = j["longitude"];
bool isApproximate = j["isApproximate"];
bool isGate = j["isGate"];
//bool isApproximate = j["isApproximate"];
//bool isGate = j["isGate"];

if (Globals::AUTONOMOUS) { // && !isApproximate && !isGate) {
navtypes::point_t waypointCoords(std::stod(latitude), std::stod(longitude), 1);
Expand Down Expand Up @@ -419,8 +420,9 @@ MissionControlProtocol::MissionControlProtocol(SingleClientWSServer& server)
validateCameraStreamCloseRequest);
this->addMessageHandler(
WAYPOINT_NAV_REQ_TYPE,
std::bind(&MissionControlProtocol::handleWaypointNavRequest, this, _1),
validateWaypointNavRequest);
std::bind(&MissionControlProtocol::handleWaypointNavRequest, this, _1));
// TODO: Add this back in
//validateWaypointNavRequest);
this->addConnectionHandler(std::bind(&MissionControlProtocol::handleConnection, this));
this->addDisconnectionHandler(
std::bind(&MissionControlProtocol::stopAndShutdownPowerRepeat, this, false));
Expand Down

0 comments on commit 4f45243

Please sign in to comment.