|
| 1 | +// |
| 2 | +// Created by qiayuan on 5/23/21. |
| 3 | +// |
| 4 | + |
| 5 | +#pragma once |
| 6 | + |
| 7 | +#include "chassis_gimbal_manual.h" |
| 8 | + |
| 9 | +#include <utility> |
| 10 | +#include <std_srvs/Empty.h> |
| 11 | +#include <actionlib/client/simple_action_client.h> |
| 12 | +#include <rm_common/decision/calibration_queue.h> |
| 13 | +#include <std_msgs/Float64.h> |
| 14 | +#include <tf2_geometry_msgs/tf2_geometry_msgs.h> |
| 15 | +#include <rm_msgs/EngineerAction.h> |
| 16 | +#include <rm_msgs/MultiDofCmd.h> |
| 17 | +#include <rm_msgs/GpioData.h> |
| 18 | +#include <rm_msgs/EngineerUi.h> |
| 19 | +#include <rm_msgs/VisualizeStateData.h> |
| 20 | +#include <stack> |
| 21 | +#include "unordered_map" |
| 22 | + |
| 23 | +namespace rm_manual |
| 24 | +{ |
| 25 | +class Engineer2Manual : public ChassisGimbalManual |
| 26 | +{ |
| 27 | +public: |
| 28 | + enum ControlMode |
| 29 | + { |
| 30 | + MANUAL, |
| 31 | + MIDDLEWARE |
| 32 | + }; |
| 33 | + |
| 34 | + enum JointMode |
| 35 | + { |
| 36 | + SERVO, |
| 37 | + JOINT |
| 38 | + }; |
| 39 | + |
| 40 | + enum GimbalMode |
| 41 | + { |
| 42 | + RATE, |
| 43 | + DIRECT |
| 44 | + }; |
| 45 | + |
| 46 | + enum SpeedMode |
| 47 | + { |
| 48 | + LOW, |
| 49 | + NORMAL, |
| 50 | + FAST, |
| 51 | + EXCHANGE, |
| 52 | + BIG_ISLAND_SPEED |
| 53 | + }; |
| 54 | + |
| 55 | + Engineer2Manual(ros::NodeHandle& nh, ros::NodeHandle& nh_referee); |
| 56 | + void run() override; |
| 57 | + |
| 58 | +private: |
| 59 | + void changeSpeedMode(SpeedMode speed_mode); |
| 60 | + void checkKeyboard(const rm_msgs::DbusData::ConstPtr& dbus_data) override; |
| 61 | + void updateRc(const rm_msgs::DbusData::ConstPtr& dbus_data) override; |
| 62 | + void updatePc(const rm_msgs::DbusData::ConstPtr& dbus_data) override; |
| 63 | + void updateServo(const rm_msgs::DbusData::ConstPtr& dbus_data); |
| 64 | + void dbusDataCallback(const rm_msgs::DbusData::ConstPtr& data) override; |
| 65 | + void gpioStateCallback(const rm_msgs::GpioData::ConstPtr& data); |
| 66 | + void stoneNumCallback(const std_msgs::String ::ConstPtr& data); |
| 67 | + void sendCommand(const ros::Time& time) override; |
| 68 | + void runStepQueue(const std::string& step_queue_name); |
| 69 | + void actionFeedbackCallback(const rm_msgs::EngineerFeedbackConstPtr& feedback); |
| 70 | + void actionDoneCallback(const actionlib::SimpleClientGoalState& state, const rm_msgs::EngineerResultConstPtr& result); |
| 71 | + |
| 72 | + void initMode(); |
| 73 | + void enterServo(); |
| 74 | + void actionActiveCallback() |
| 75 | + { |
| 76 | + operating_mode_ = MIDDLEWARE; |
| 77 | + } |
| 78 | + void remoteControlTurnOff() override; |
| 79 | + void chassisOutputOn() override; |
| 80 | + void gimbalOutputOn() override; |
| 81 | + |
| 82 | + void rightSwitchUpRise() override; |
| 83 | + void rightSwitchMidRise() override; |
| 84 | + void rightSwitchDownRise() override; |
| 85 | + void leftSwitchUpRise() override; |
| 86 | + void leftSwitchUpFall(); |
| 87 | + void leftSwitchDownRise() override; |
| 88 | + void leftSwitchDownFall(); |
| 89 | + void ctrlAPress(); |
| 90 | + void ctrlBPress(); |
| 91 | + void ctrlBPressing(); |
| 92 | + void ctrlBRelease(); |
| 93 | + void ctrlCPress(); |
| 94 | + void ctrlDPress(); |
| 95 | + void ctrlEPress(); |
| 96 | + void ctrlFPress(); |
| 97 | + void ctrlGPress(); |
| 98 | + void ctrlQPress(); |
| 99 | + void ctrlRPress(); |
| 100 | + void ctrlSPress(); |
| 101 | + void ctrlVPress(); |
| 102 | + void ctrlVRelease(); |
| 103 | + void ctrlWPress(); |
| 104 | + void ctrlXPress(); |
| 105 | + void ctrlZPress(); |
| 106 | + |
| 107 | + void bPressing(); |
| 108 | + void bRelease(); |
| 109 | + void cPressing(); |
| 110 | + void cRelease(); |
| 111 | + void ePressing(); |
| 112 | + void eRelease(); |
| 113 | + void fPress(); |
| 114 | + void fRelease(); |
| 115 | + void gPress(); |
| 116 | + void gRelease(); |
| 117 | + void qPressing(); |
| 118 | + void qRelease(); |
| 119 | + void rPress(); |
| 120 | + void rRelease(); |
| 121 | + void vPressing(); |
| 122 | + void vRelease(); |
| 123 | + void xPress(); |
| 124 | + void zPressing(); |
| 125 | + void zRelease(); |
| 126 | + |
| 127 | + void shiftPressing(); |
| 128 | + void shiftRelease(); |
| 129 | + void shiftBPress(); |
| 130 | + void shiftBRelease(); |
| 131 | + void shiftCPress(); |
| 132 | + void shiftEPress(); |
| 133 | + void shiftFPress(); |
| 134 | + void shiftGPress(); |
| 135 | + void shiftQPress(); |
| 136 | + void shiftRPress(); |
| 137 | + void shiftRRelease(); |
| 138 | + void shiftVPress(); |
| 139 | + void shiftVRelease(); |
| 140 | + void shiftXPress(); |
| 141 | + void shiftZPress(); |
| 142 | + void shiftZRelease(); |
| 143 | + |
| 144 | + void mouseLeftRelease(); |
| 145 | + void mouseRightRelease(); |
| 146 | + |
| 147 | + // Servo |
| 148 | + |
| 149 | + bool mouse_left_pressed_{}, mouse_right_pressed_{}, had_ground_stone_{ false }, main_gripper_on_{ false }, |
| 150 | + had_side_gold_{ false }, stone_state_[4]{}; |
| 151 | + double angular_z_scale_{}, gyro_scale_{}, fast_gyro_scale_{}, low_gyro_scale_{}, normal_gyro_scale_{}, |
| 152 | + exchange_gyro_scale_{}, fast_speed_scale_{}, low_speed_scale_{}, normal_speed_scale_{}, exchange_speed_scale_{}, |
| 153 | + big_island_speed_scale_{}; |
| 154 | + |
| 155 | + std::string prefix_{}, root_{}, exchange_direction_{ "left" }, exchange_arm_position_{ "normal" }; |
| 156 | + int operating_mode_{}, servo_mode_{ 1 }, gimbal_mode_{}, gimbal_direction_{ 0 }; |
| 157 | + |
| 158 | + std::stack<std::string> stone_num_{}; |
| 159 | + |
| 160 | + ros::Time last_time_; |
| 161 | + ros::Subscriber stone_num_sub_, gripper_state_sub_; |
| 162 | + ros::Publisher engineer_ui_pub_, gripper_ui_pub_; |
| 163 | + |
| 164 | + rm_msgs::GpioData gpio_state_; |
| 165 | + rm_msgs::EngineerUi engineer_ui_, old_ui_; |
| 166 | + rm_msgs::VisualizeStateData gripper_ui_; |
| 167 | + |
| 168 | + rm_common::Vel3DCommandSender* servo_command_sender_; |
| 169 | + rm_common::ServiceCallerBase<std_srvs::Empty>* servo_reset_caller_; |
| 170 | + rm_common::CalibrationQueue* calibration_gather_{}; |
| 171 | + |
| 172 | + actionlib::SimpleActionClient<rm_msgs::EngineerAction> action_client_; |
| 173 | + |
| 174 | + InputEvent left_switch_up_event_, left_switch_down_event_, ctrl_a_event_, ctrl_b_event_, ctrl_c_event_, ctrl_d_event_, |
| 175 | + ctrl_e_event_, ctrl_f_event_, ctrl_g_event_, ctrl_q_event_, ctrl_r_event_, ctrl_s_event_, ctrl_v_event_, |
| 176 | + ctrl_w_event_, ctrl_x_event_, ctrl_z_event_, b_event_, c_event_, e_event_, f_event_, g_event_, q_event_, r_event_, |
| 177 | + v_event_, x_event_, z_event_, shift_event_, shift_b_event_, shift_c_event_, shift_e_event_, shift_f_event_, |
| 178 | + shift_g_event_, shift_v_event_, shift_q_event_, shift_r_event_, shift_x_event_, shift_z_event_, mouse_left_event_, |
| 179 | + mouse_right_event_; |
| 180 | + |
| 181 | + std::unordered_map<std::string, int> stoneNumMap_ = { |
| 182 | + { "+g", 0 }, { "+s1", 1 }, { "+s2", 2 }, { "+s3", 3 }, { "-g", 0 }, { "-s1", 1 }, { "-s2", 2 }, { "-s3", 3 }, |
| 183 | + }; |
| 184 | + |
| 185 | + enum UiState |
| 186 | + { |
| 187 | + NONE, |
| 188 | + BIG_ISLAND, |
| 189 | + SMALL_ISLAND |
| 190 | + }; |
| 191 | +}; |
| 192 | + |
| 193 | +} // namespace rm_manual |
0 commit comments