Skip to content

Commit 6fcb259

Browse files
authored
Cleanup (#359)
* Remove active suspension * Add drillActuator and drillMotor as joints, remove motor request/reports * Remove lidar * Fix typo * Fix formatting * Fix merge * Fix format
1 parent cb2db73 commit 6fcb259

File tree

12 files changed

+38
-64
lines changed

12 files changed

+38
-64
lines changed

README.md

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -125,7 +125,7 @@ make -j Rover
125125
Launch the appropriate simulator executable for your platform. Then, run the rover code, using the `p` flag to specify a peripheral:
126126

127127
```bash
128-
./Rover -p {none|arm|science|lidar}
128+
./Rover -p {none|arm|science}
129129
```
130130

131131
The programs can be started in any order, it doesn't matter.

rover-config/50-usb-hokuyo-lidar.rules

Lines changed: 0 additions & 1 deletion
This file was deleted.

rover-config/README.md

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -8,7 +8,6 @@ filesystem.
88

99
| **File/Directory** | **Location on Rover** | **Description** |
1010
| ----------------- | -------------------- | -------------- |
11-
| `50-usb-hokuyo-lidar.rules` | `/etc/udev/rules.d/` | `udev` rules for making sure we have permissions to access the lidar over USB. |
1211
| `50-rover-cameras.rules` | `/etc/udev/rules.d/` | `udev` rules for making sure cameras have stable IDs. |
1312

1413
# Directions

src/Constants.cpp

Lines changed: 0 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -100,14 +100,6 @@ const double LANDMARK_WAYPOINT_RADIUS = Constants::ROBOT_LENGTH * 1.3;
100100
const double EPS = 2.0; // heuristic weight for weighted A*
101101
} // namespace Nav
102102

103-
// Lidar
104-
namespace Lidar {
105-
const std::string RP_PATH = "/dev/ttyUSB0";
106-
const double MM_PER_M = 1000;
107-
const uint32_t RPLIDAR_A1_BAUDRATE = 115200;
108-
const uint32_t RPLIDAR_S1_BAUDRATE = 256000;
109-
} // namespace Lidar
110-
111103
// Video encoding
112104
namespace video {
113105
const int H264_RF_CONSTANT = 40;

src/Constants.h

Lines changed: 22 additions & 29 deletions
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,10 @@
1010

1111
#include <frozen/unordered_map.h>
1212

13+
using robot::types::CameraID;
14+
using robot::types::jointid_t;
15+
using robot::types::motorid_t;
16+
1317
namespace Constants {
1418
// TODO: make sure these are still accurate with the new arm.
1519
extern const double SHOULDER_LENGTH;
@@ -54,13 +58,13 @@ extern const double MAX_DTHETA;
5458
// TODO: We need to recalibrate the camera, since we replaced it with a different one.
5559
// TODO: rename cameras (in MC as well) as appropriate
5660
extern const char* MAST_CAMERA_CONFIG_PATH;
57-
extern const robot::types::CameraID MAST_CAMERA_ID;
61+
extern const CameraID MAST_CAMERA_ID;
5862

5963
extern const char* FOREARM_CAMERA_CONFIG_PATH;
60-
extern const robot::types::CameraID FOREARM_CAMERA_ID;
64+
extern const CameraID FOREARM_CAMERA_ID;
6165

6266
extern const char* HAND_CAMERA_CONFIG_PATH;
63-
extern const robot::types::CameraID HAND_CAMERA_ID;
67+
extern const CameraID HAND_CAMERA_ID;
6468

6569
extern const uint16_t WS_SERVER_PORT;
6670

@@ -104,14 +108,6 @@ extern const double LANDMARK_WAYPOINT_RADIUS;
104108
extern const double EPS;
105109
} // namespace Nav
106110

107-
// Lidar
108-
namespace Lidar {
109-
extern const std::string RP_PATH;
110-
extern const double MM_PER_M;
111-
extern const uint32_t RPLIDAR_A1_BAUDRATE;
112-
extern const uint32_t RPLIDAR_S1_BAUDRATE;
113-
} // namespace Lidar
114-
115111
// Video encoding
116112
namespace video {
117113
/**
@@ -126,22 +122,21 @@ extern const int H264_RF_CONSTANT;
126122
/**
127123
* @brief Stream-specific RF constants.
128124
*/
129-
extern const std::unordered_map<robot::types::CameraID, int> STREAM_RFS;
125+
extern const std::unordered_map<CameraID, int> STREAM_RFS;
130126
} // namespace video
131127

132128
/**
133129
* A map that pairs each of the joints to its corresponding motor.
134130
* (one-to-one pairs only)
135131
*/
136-
constexpr auto JOINT_MOTOR_MAP =
137-
frozen::make_unordered_map<robot::types::jointid_t, robot::types::motorid_t>(
138-
{{robot::types::jointid_t::armBase, robot::types::motorid_t::armBase},
139-
{robot::types::jointid_t::shoulder, robot::types::motorid_t::shoulder},
140-
{robot::types::jointid_t::elbow, robot::types::motorid_t::elbow},
141-
{robot::types::jointid_t::forearm, robot::types::motorid_t::forearm},
142-
{robot::types::jointid_t::hand, robot::types::motorid_t::hand},
143-
{robot::types::jointid_t::activeSuspension,
144-
robot::types::motorid_t::activeSuspension}});
132+
constexpr auto JOINT_MOTOR_MAP = frozen::make_unordered_map<jointid_t, motorid_t>(
133+
{{jointid_t::armBase, motorid_t::armBase},
134+
{jointid_t::shoulder, motorid_t::shoulder},
135+
{jointid_t::elbow, motorid_t::elbow},
136+
{jointid_t::forearm, motorid_t::forearm},
137+
{jointid_t::hand, motorid_t::hand},
138+
{jointid_t::drillActuator, motorid_t::drillActuator},
139+
{jointid_t::drillMotor, motorid_t::drillMotor}});
145140

146141
// Arm inverse kinematics
147142
namespace arm {
@@ -162,27 +157,25 @@ extern const int IK_SOLVER_MAX_ITER;
162157
* The joints corresponding to the motors used for IK in the arm. The ordering in this array is
163158
* the canonical ordering of these joints for IK purposes.
164159
*/
165-
extern const std::array<robot::types::jointid_t, 2> IK_MOTOR_JOINTS;
160+
extern const std::array<jointid_t, 2> IK_MOTOR_JOINTS;
166161

167162
/**
168163
* The motors used in IK. The i-th element in this array corresponds to the joint in the i-th
169164
* element of `IK_MOTOR_JOINTS`
170165
*/
171-
extern const std::array<robot::types::motorid_t, 2> IK_MOTORS;
166+
extern const std::array<motorid_t, 2> IK_MOTORS;
172167

173168
/**
174169
* Map from motor ids to min and max joint limits in millidegrees
175170
*/
176-
constexpr frozen::unordered_map<robot::types::motorid_t, std::pair<int, int>, IK_MOTORS.size()>
177-
JOINT_LIMITS{{robot::types::motorid_t::shoulder, {18200, 152500}},
178-
{robot::types::motorid_t::elbow, {-169100, 0}}};
171+
constexpr frozen::unordered_map<motorid_t, std::pair<int, int>, IK_MOTORS.size()> JOINT_LIMITS{
172+
{motorid_t::shoulder, {18200, 152500}}, {motorid_t::elbow, {-169100, 0}}};
179173

180174
/**
181175
* Map from motor ids to segment length in meters
182176
*/
183-
constexpr frozen::unordered_map<robot::types::motorid_t, double, IK_MOTORS.size()>
184-
SEGMENT_LENGTHS{{robot::types::motorid_t::shoulder, 0.3848608},
185-
{robot::types::motorid_t::elbow, 0.461264}};
177+
constexpr frozen::unordered_map<motorid_t, double, IK_MOTORS.size()> SEGMENT_LENGTHS{
178+
{motorid_t::shoulder, 0.3848608}, {motorid_t::elbow, 0.461264}};
186179
} // namespace arm
187180

188181
namespace autonomous {

src/Rover.cpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -43,8 +43,7 @@ void parseCommandLine(int argc, char** argv) {
4343
{"none", mountedperipheral_t::none},
4444
{"arm", mountedperipheral_t::arm},
4545
{"armServo", mountedperipheral_t::armServo},
46-
{"science", mountedperipheral_t::scienceStation},
47-
{"lidar", mountedperipheral_t::lidar}};
46+
{"science", mountedperipheral_t::scienceStation}};
4847

4948
if (allowed.find(value) != allowed.end()) {
5049
Globals::mountedPeripheral = allowed[value];

src/TunePID.cpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,6 @@ const std::map<motorid_t, std::string> motorNameMap = {
4545
{motorid_t::wristDiffRight, "wristDiffRight"},
4646
{motorid_t::wristDiffLeft, "wristDiffLeft"},
4747
{motorid_t::hand, "hand"},
48-
{motorid_t::activeSuspension, "activeSuspension"},
4948
{motorid_t::drillActuator, "drillActuator"},
5049
{motorid_t::drillMotor, "drillMotor"}};
5150

src/network/MissionControlMessages.h

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -3,22 +3,19 @@
33
namespace net::mc {
44

55
// TODO: possibly use frozen::string for this so we don't have to use raw char ptrs
6-
// TODO: MOTOR_POS_REQ, MOTOR_STATUS_REP are unimplemented, do we want to remove or implement?
76
// request keys
87
constexpr const char* EMERGENCY_STOP_REQ_TYPE = "emergencyStopRequest";
98
constexpr const char* OPERATION_MODE_REQ_TYPE = "operationModeRequest";
109
constexpr const char* DRIVE_REQ_TYPE = "driveRequest";
1110
constexpr const char* DRIVE_TANK_REQ_TYPE = "tankDriveRequest";
1211
constexpr const char* ARM_IK_ENABLED_TYPE = "requestArmIKEnabled";
1312
constexpr const char* JOINT_POWER_REQ_TYPE = "jointPowerRequest";
14-
constexpr const char* MOTOR_POSITION_REQ_TYPE = "motorPositionRequest";
1513
constexpr const char* JOINT_POSITION_REQ_TYPE = "jointPositionRequest";
1614
constexpr const char* CAMERA_STREAM_OPEN_REQ_TYPE = "cameraStreamOpenRequest";
1715
constexpr const char* CAMERA_STREAM_CLOSE_REQ_TYPE = "cameraStreamCloseRequest";
1816
constexpr const char* WAYPOINT_NAV_REQ_TYPE = "waypointNavRequest";
1917

2018
// report keys
21-
constexpr const char* MOTOR_STATUS_REP_TYPE = "motorStatusReport";
2219
constexpr const char* CAMERA_STREAM_REP_TYPE = "cameraStreamReport";
2320
constexpr const char* MOUNTED_PERIPHERAL_REP_TYPE = "mountedPeripheralReport";
2421
constexpr const char* JOINT_POSITION_REP_TYPE = "jointPositionReport";

src/world_interface/data.cpp

Lines changed: 4 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -44,12 +44,14 @@ std::string to_string(robot::types::jointid_t joint) {
4444
return "wristPitch";
4545
case jointid_t::wristRoll:
4646
return "wristRoll";
47-
case jointid_t::activeSuspension:
48-
return "activeSuspension";
4947
case jointid_t::ikUp:
5048
return "ikUp";
5149
case jointid_t::ikForward:
5250
return "ikForward";
51+
case jointid_t::drillActuator:
52+
return "drillActuator";
53+
case jointid_t::drillMotor:
54+
return "drillMotor";
5355
default:
5456
// should never happen
5557
return "<unknown>";
@@ -73,9 +75,6 @@ std::string to_string(robot::types::mountedperipheral_t peripheral) {
7375
case mountedperipheral_t::armServo:
7476
return "armServo";
7577

76-
case mountedperipheral_t::lidar:
77-
return "lidar";
78-
7978
case mountedperipheral_t::scienceStation:
8079
return "scienceStation";
8180

src/world_interface/data.h

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -64,7 +64,6 @@ enum class motorid_t {
6464
wristDiffRight,
6565
wristDiffLeft,
6666
hand,
67-
activeSuspension,
6867
drillActuator,
6968
drillMotor
7069
};
@@ -75,7 +74,6 @@ enum class mountedperipheral_t {
7574
arm,
7675
armServo,
7776
scienceStation,
78-
lidar
7977
};
8078

8179
enum class jointid_t {
@@ -86,15 +84,16 @@ enum class jointid_t {
8684
wristPitch,
8785
wristRoll,
8886
hand,
89-
activeSuspension,
9087
ikForward,
91-
ikUp
88+
ikUp,
89+
drillActuator,
90+
drillMotor
9291
};
9392

9493
constexpr auto all_jointid_t = frozen::make_unordered_set<jointid_t>(
9594
{jointid_t::armBase, jointid_t::shoulder, jointid_t::elbow, jointid_t::forearm,
96-
jointid_t::wristRoll, jointid_t::wristPitch, jointid_t::hand, jointid_t::activeSuspension,
97-
jointid_t::ikForward, jointid_t::ikUp});
95+
jointid_t::wristRoll, jointid_t::wristPitch, jointid_t::hand, jointid_t::ikForward,
96+
jointid_t::ikUp, jointid_t::drillActuator, jointid_t::drillMotor});
9897

9998
constexpr auto name_to_jointid = frozen::make_unordered_map<frozen::string, jointid_t>(
10099
{{"armBase", jointid_t::armBase},
@@ -104,9 +103,10 @@ constexpr auto name_to_jointid = frozen::make_unordered_map<frozen::string, join
104103
{"wristPitch", jointid_t::wristPitch},
105104
{"wristRoll", jointid_t::wristRoll},
106105
{"hand", jointid_t::hand},
107-
{"activeSuspension", jointid_t::activeSuspension},
108106
{"ikForward", jointid_t::ikForward},
109-
{"ikUp", jointid_t::ikUp}});
107+
{"ikUp", jointid_t::ikUp},
108+
{"drillActuator", jointid_t::drillActuator},
109+
{"drillMotor", jointid_t::drillMotor}});
110110

111111
class bad_datapoint_access : public std::runtime_error {
112112
public:

0 commit comments

Comments
 (0)