Skip to content

Commit

Permalink
Renamed arm packet and added comments
Browse files Browse the repository at this point in the history
  • Loading branch information
Geeoon committed Oct 3, 2023
1 parent 5adaa35 commit 7947461
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 5 deletions.
11 changes: 7 additions & 4 deletions src/network/MissionControlProtocol.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ const std::chrono::milliseconds TELEM_REPORT_PERIOD = 100ms;
constexpr const char* EMERGENCY_STOP_REQ_TYPE = "emergencyStopRequest";
constexpr const char* OPERATION_MODE_REQ_TYPE = "operationModeRequest";
constexpr const char* DRIVE_REQ_TYPE = "driveRequest";
constexpr const char* ARM_IK_ENABLED_TYPE = "setArmIKEnabled";
constexpr const char* ARM_IK_ENABLED_TYPE = "requestArmIKEnabled";
constexpr const char* MOTOR_POWER_REQ_TYPE = "motorPowerRequest";
constexpr const char* JOINT_POWER_REQ_TYPE = "jointPowerRequest";
constexpr const char* MOTOR_POSITION_REQ_TYPE = "motorPositionRequest";
Expand Down Expand Up @@ -128,7 +128,7 @@ void MissionControlProtocol::handleDriveRequest(const json& j) {
this->setRequestedCmdVel(dtheta, dx);
}

void MissionControlProtocol::handleSetArmIKEnabled(const json& j) {
void MissionControlProtocol::handleRequestArmIKEnabled(const json& j) {
bool enabled = j["enabled"];
if (enabled) {
Globals::armIKEnabled = false;
Expand All @@ -140,6 +140,9 @@ void MissionControlProtocol::handleSetArmIKEnabled(const json& j) {
// TODO: there should be a better way of handling invalid data than crashing.
// It should somehow just not enable IK, but then it needs to communicate back to MC
// that IK wasn't enabled?
// FIX: Change setArmIKOn to requestArmIkOn.
// Create new packet: confirmIKOn packet
// Rover responds with confirmIKOn after requestArmIKOn is processed
assert(armJointPositions.isValid());
Globals::planarArmController.set_setpoint(armJointPositions.getData());
Globals::armIKEnabled = true;
Expand Down Expand Up @@ -361,11 +364,11 @@ MissionControlProtocol::MissionControlProtocol(SingleClientWSServer& server)
validateDriveRequest);
this->addMessageHandler(
ARM_IK_ENABLED_TYPE,
std::bind(&MissionControlProtocol::handleSetArmIKEnabled, this, _1),
std::bind(&MissionControlProtocol::handleRequestArmIKEnabled, this, _1),
validateArmIKEnable);
this->addMessageHandler(
ARM_IK_ENABLED_TYPE,
std::bind(&MissionControlProtocol::handleSetArmIKEnabled, this, _1),
std::bind(&MissionControlProtocol::handleRequestArmIKEnabled, this, _1),
validateArmIKEnable);
this->addMessageHandler(
JOINT_POWER_REQ_TYPE,
Expand Down
2 changes: 1 addition & 1 deletion src/network/MissionControlProtocol.h
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ class MissionControlProtocol : public WebSocketProtocol { // TODO: add documenta
void handleCameraStreamCloseRequest(const json& j);
void handleJointPowerRequest(const json& j);
void handleDriveRequest(const json& j);
void handleSetArmIKEnabled(const json& j);
void handleRequestArmIKEnabled(const json& j);
void sendCameraStreamReport(const CameraID& cam,
const std::vector<std::basic_string<uint8_t>>& videoData);
void sendJointPositionReport(const std::string& jointName, int32_t position);
Expand Down

0 comments on commit 7947461

Please sign in to comment.