Skip to content

Commit

Permalink
Remove deprecated and vestigial methods from world interface (#320)
Browse files Browse the repository at this point in the history
* Remove deprecated and vestigial methods from world interface

* More cleanup
  • Loading branch information
abhaybd authored May 1, 2024
1 parent ddc59d4 commit 73c1b17
Show file tree
Hide file tree
Showing 6 changed files with 0 additions and 97 deletions.
34 changes: 0 additions & 34 deletions src/Rover.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,6 @@
#include <csignal>
#include <ctime>
#include <filesystem>
#include <fstream>
#include <loguru.cpp>
#include <sstream>
#include <thread>
Expand All @@ -33,39 +32,6 @@ void closeRover(int signum) {
raise(SIGTERM);
}

std::vector<URCLegGPS> parseGPSLegs(std::string filepath) {
std::vector<URCLegGPS> urc_legs;
std::ifstream gps_legs(filepath);

int left_post_id, right_post_id;
double lat, lon;
std::string line;

// A properly formatted file has each leg on a separate line, with each line of the form
// left_post_id right_post_id lat lon
// Improperly formatted lines (empty lines, comments) are ignored, and text
// after the above data on properly formatted lines is ignored
// An example can be found at example_gps_legs.txt
while (getline(gps_legs, line)) {
std::istringstream line_stream(line);
if (line_stream >> left_post_id >> right_post_id >> lat >> lon) {
// we assume that gps already has a fix
gpscoords_t gps = {lat, lon};
URCLegGPS leg = {left_post_id, right_post_id, gps};
LOG_F(INFO, "Got urc leg at lat=%f lon=%f", lat, lon);
urc_legs.push_back(leg);
}
}
LOG_F(INFO, "Got %ld urc legs\n", urc_legs.size());

if (urc_legs.size() == 0) {
LOG_F(ERROR, "could not get URC legs");
std::exit(EXIT_FAILURE);
}

return urc_legs;
}

void parseCommandLine(int argc, char** argv) {
argparse::ArgumentParser program("Rover", "N/A");

Expand Down
18 changes: 0 additions & 18 deletions src/navtypes.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,11 +25,6 @@ struct eulerangles_t {
double yaw;
};

/* Obstacles are specifed as a list of 2D vertices. Must be convex.
* Do not repeat the starting vertex at the end. */
using obstacle_t = Eigen::ArrayX2d;
using obstacles_t = std::vector<obstacle_t>;

using pose_t = Eigen::Vector3d; // Robot pose: x, y, theta
using transform_t = Eigen::Matrix3d; // a pose in matrix form; see toPose below
using trajectory_t = std::vector<transform_t>;
Expand All @@ -44,18 +39,5 @@ using point_t =
Eigen::Vector3d; // x, y, 1 (or 0, 0, 0 to represent "no data")
// The 1 at the end makes calculating affine transforms easier.
using points_t = std::vector<point_t>;
using traj_points_t = std::vector<points_t>; // points_t for each time along a trajectory

struct URCLeg {
int left_post_id;
int right_post_id; // This will be -1 for legs that are just single posts
point_t approx_GPS;
};

struct URCLegGPS {
int left_post_id;
int right_post_id;
gpscoords_t gps;
};

} // namespace navtypes
8 changes: 0 additions & 8 deletions src/world_interface/noop_world.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,14 +47,6 @@ DataPoint<pose_t> getTruePose() {
return {};
}

DataPoint<pose_t> readVisualOdomVel() {
return DataPoint<pose_t>{};
}

URCLeg getLeg(int /*id*/) {
return URCLeg{-1, -1, {0., 0., 0.}};
}

void setMotorPower(motorid_t motor, double normalizedPWM) {}

void setMotorPos(motorid_t motor, int32_t targetPos) {}
Expand Down
8 changes: 0 additions & 8 deletions src/world_interface/real_world_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -234,14 +234,6 @@ landmarks_t readLandmarks() {
return {};
}

DataPoint<pose_t> readVisualOdomVel() {
return DataPoint<pose_t>{};
}

URCLeg getLeg(int index) {
return URCLeg{0, -1, {0., 0., 0.}};
}

template <typename T>
int getIndex(const std::vector<T>& vec, const T& val) {
auto itr = std::find(vec.begin(), vec.end(), val);
Expand Down
8 changes: 0 additions & 8 deletions src/world_interface/simulator_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -338,10 +338,6 @@ landmarks_t readLandmarks() {
return {};
}

DataPoint<pose_t> readVisualOdomVel() {
return DataPoint<pose_t>{};
}

DataPoint<Eigen::Quaterniond> readIMU() {
std::lock_guard<std::mutex> guard(orientationMutex);
return lastOrientation;
Expand All @@ -352,10 +348,6 @@ DataPoint<pose_t> getTruePose() {
return lastTruePose;
}

URCLeg getLeg(int index) {
return URCLeg{0, -1, {0., 0., 0.}};
}

void setMotorPower(motorid_t motor, double normalizedPWM) {
std::shared_ptr<robot::base_motor> motor_ptr = getMotor(motor);
motor_ptr->setMotorPower(normalizedPWM);
Expand Down
21 changes: 0 additions & 21 deletions src/world_interface/world_interface.h
Original file line number Diff line number Diff line change
Expand Up @@ -171,25 +171,6 @@ types::DataPoint<navtypes::pose_t> getTruePose();
*/
std::optional<navtypes::point_t> gpsToMeters(const navtypes::gpscoords_t& coord);

/**
* @brief Calculate the current pose velocity (in the robot's reference frame) using visual
* odometry.
*
* @return types::DataPoint<navtypes::pose_t> The current velocity in each axis of the pose
* vector, or an empty data point if no data is available.
*/
types::DataPoint<navtypes::pose_t> readVisualOdomVel();

/**
* @brief Get the URC leg of the given index.
*
* @param index The index of the URC leg, in the range [0, 6]
* @return navtypes::URCLeg Information for the URC leg of the given index.
*
* @deprecated This function is probably deprecated, and will be replaced in the future.
*/
navtypes::URCLeg getLeg(int index);

/**
* @brief Set the robot indicator to indicate the given signal.
*
Expand Down Expand Up @@ -291,8 +272,6 @@ getMotorPositionsRad(const std::array<types::motorid_t, N>& motors) {
return types::DataPoint<navtypes::Vectord<N>>(timestamp.value(), motorPositions);
}

// TODO: document
void zeroJoint(robot::types::jointid_t joint);
} // namespace robot

namespace gps {
Expand Down

0 comments on commit 73c1b17

Please sign in to comment.