Resurgence (PY2022)
Codebase for the Husky Robotics 2021-2022 rover Resurgence
Loading...
Searching...
No Matches
MissionControlProtocol.h
1#pragma once
2
3#include "../autonomous/AutonomousTask.h"
4#include "../utils/scheduler.h"
5#include "../video/H264Encoder.h"
6#include "../world_interface/world_interface.h"
7#include "MissionControlTasks.h"
8#include "websocket/WebSocketProtocol.h"
9#include "websocket/WebSocketServer.h"
10
11#include <atomic>
12#include <condition_variable>
13#include <memory>
14#include <optional>
15#include <shared_mutex>
16#include <thread>
17#include <unordered_map>
18#include <unordered_set>
19
20namespace net {
21namespace mc {
22
23using json = nlohmann::json;
25using robot::types::jointid_t;
26using websocket::SingleClientWSServer;
27using websocket::WebSocketProtocol;
28
29class MissionControlProtocol : public WebSocketProtocol { // TODO: add documentation
30public:
31 MissionControlProtocol(SingleClientWSServer& server);
32 ~MissionControlProtocol();
33 MissionControlProtocol(const MissionControlProtocol& other) = delete;
34 MissionControlProtocol& operator=(const MissionControlProtocol& other) = delete;
35
36private:
37 SingleClientWSServer& _server;
38 tasks::PowerRepeatTask _power_repeat_task;
39 tasks::CameraStreamTask _camera_stream_task;
40 tasks::TelemReportTask _telem_report_task;
41 tasks::ArmIKTask _arm_ik_task;
42 autonomous::AutonomousTask _autonomous_task;
43
44 void handleEmergencyStopRequest(const json& j);
45 void handleOperationModeRequest(const json& j);
46 void handleDriveModeRequest(const json& j);
47 void handleTankDriveRequest(const json& j);
48 void handleTurnInPlaceDriveRequest(const json& j);
49 void handleCrabDriveRequest(const json& j);
50 void handleCameraStreamOpenRequest(const json& j);
51 void handleCameraStreamCloseRequest(const json& j);
52 void handleJointPowerRequest(const json& j);
53 void handleWaypointNavRequest(const json& j);
54 void handleDriveRequest(const json& j);
55 void handleRequestArmIKEnabled(const json& j);
56 void sendArmIKEnabledReport(bool enabled);
57 void handleConnection();
58 void handleHeartbeatTimedOut();
59 void stopAndShutdownPowerRepeat(bool sendDisableIK);
60 void setArmIKEnabled(bool enabled, bool sendReport = true);
61 void setRequestedJointPower(jointid_t joint, double power);
62 void setRequestedCmdVel(double dtheta, double dx);
63 void setRequestedTankCmdVel(double left, double right);
64 void setRequestedTurnInPlaceCmdVel(double dtheta);
65 void setRequestedCrabCmdVel(double dtheta, double dy);
66};
67
68}; // namespace mc
69} // namespace net
_Tp power(_Tp __x, _Integer __n, _MonoidOperation __monoid_op)
ios_base & right(ios_base &__base)
ios_base & left(ios_base &__base)
Definition AutonomousTask.h:15
This task sets the arm joint positions to track the current IK command.
Definition MissionControlTasks.h:120
This task is responsible for sending the camera streams to Mission Control over websocket.
Definition MissionControlTasks.h:72
This task is responsible for periodically resending setMotorPower commands to the motors.
Definition MissionControlTasks.h:20
This task periodically sends robot telemetry data to Mission Control.
Definition MissionControlTasks.h:105
WebSocketProtocol(const std::string &protocolPath)
Construct a new WebSocket protocol.
Definition WebSocketProtocol.cpp:11
basic_json<> json
std::string CameraID
The type of a camera id.
Definition data.h:46