From aed1ebf8af2d4c20cfc3c74f4e3b0e09bab9b9b5 Mon Sep 17 00:00:00 2001 From: Kerim Satirli Date: Tue, 30 Jul 2024 16:38:40 +0200 Subject: [PATCH 1/5] extraneous whitespace linting --- General_Driver/AK09918.h | 3 +- General_Driver/General_Driver.ino | 10 +++--- General_Driver/IMU.cpp | 32 +++++++++---------- General_Driver/RoArm-M2_module.h | 52 +++++++++++++++---------------- General_Driver/json_cmd.h | 14 ++++----- General_Driver/movtion_module.h | 10 +++--- General_Driver/oled_ctrl.h | 2 +- General_Driver/uart_ctrl.h | 10 +++--- General_Driver/ugv_config.h | 4 +-- General_Driver/web_page.h | 4 +-- General_Driver/wifi_ctrl.h | 10 +++--- 11 files changed, 75 insertions(+), 76 deletions(-) diff --git a/General_Driver/AK09918.h b/General_Driver/AK09918.h index 9889bc9..49deaf3 100644 --- a/General_Driver/AK09918.h +++ b/General_Driver/AK09918.h @@ -48,7 +48,7 @@ #define AK09918_RSV1 0x02 // Reserved 1 #define AK09918_RSV2 0x03 // Reserved 2 #define AK09918_ST1 0x10 // DataStatus 1 -#define AK09918_HXL 0x11 // X-axis data +#define AK09918_HXL 0x11 // X-axis data #define AK09918_HXH 0x12 #define AK09918_HYL 0x13 // Y-axis data #define AK09918_HYH 0x14 @@ -93,7 +93,6 @@ enum AK09918_err_type_t { AK09918_ERR_OVERFLOW = 5, // sensor overflow, means |x|+|y|+|z| >= 4912uT AK09918_ERR_WRITE_FAILED = 6, // fail to write AK09918_ERR_READ_FAILED = 7, // fail to read - }; typedef struct imu_st_sensor_data_tag diff --git a/General_Driver/General_Driver.ino b/General_Driver/General_Driver.ino index 23c2adc..eb164b6 100644 --- a/General_Driver/General_Driver.ino +++ b/General_Driver/General_Driver.ino @@ -152,7 +152,7 @@ void setup() { oled_update(); if(InfoPrint == 1){Serial.println("Power up the servos.");} delay(500); - + // init servo ctrl functions. screenLine_2 = screenLine_3; screenLine_3 = "ServoCtrl init UART2TTL..."; @@ -238,7 +238,7 @@ void loop() { case 2: moduleType_Gimbal();break; } - // recv esp-now json cmd. + // receive esp-now json cmd. if(runNewJsonCmd) { jsonCmdReceiveHandler(); jsonCmdReceive.clear(); @@ -248,11 +248,11 @@ void loop() { getLeftSpeed(); LeftPidControllerCompute(); - + getRightSpeed(); - + RightPidControllerCompute(); - + oledInfoUpdate(); updateIMUData(); diff --git a/General_Driver/IMU.cpp b/General_Driver/IMU.cpp index fbe1420..974858c 100644 --- a/General_Driver/IMU.cpp +++ b/General_Driver/IMU.cpp @@ -25,7 +25,7 @@ double declination_shenzhen = -3.22; #define Ki 1.0f // integral gain governs rate of convergence of gyroscope biases float angles[3]; -float q0, q1, q2, q3; +float q0, q1, q2, q3; void imuInit() { @@ -84,7 +84,7 @@ void imuDataGet(EulerAngles *pstAngles, MotionVal[8]=pstMagnRawData->s16Z; imuAHRSupdate((float)MotionVal[0] * 0.0175, (float)MotionVal[1] * 0.0175, (float)MotionVal[2] * 0.0175, - (float)MotionVal[3], (float)MotionVal[4], (float)MotionVal[5], + (float)MotionVal[3], (float)MotionVal[4], (float)MotionVal[5], (float)MotionVal[6], (float)MotionVal[7], MotionVal[8]); pstAngles->pitch = asin(-2 * q1 * q3 + 2 * q0* q2)* 57.3; // pitch @@ -99,7 +99,7 @@ void imuDataGet(EulerAngles *pstAngles, pstAccelRawData->Y = acc[1]; pstAccelRawData->Z = acc[2]; - return; + return; } void imuAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz) @@ -117,16 +117,16 @@ void imuAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, f float q1q1 = q1 * q1; float q1q2 = q1 * q2; float q1q3 = q1 * q3; - float q2q2 = q2 * q2; + float q2q2 = q2 * q2; float q2q3 = q2 * q3; - float q3q3 = q3 * q3; + float q3q3 = q3 * q3; - norm = invSqrt(ax * ax + ay * ay + az * az); + norm = invSqrt(ax * ax + ay * ay + az * az); ax = ax * norm; ay = ay * norm; az = az * norm; - norm = invSqrt(mx * mx + my * my + mz * mz); + norm = invSqrt(mx * mx + my * my + mz * mz); mx = mx * norm; my = my * norm; mz = mz * norm; @@ -134,9 +134,9 @@ void imuAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, f // compute reference direction of flux hx = 2 * mx * (0.5f - q2q2 - q3q3) + 2 * my * (q1q2 - q0q3) + 2 * mz * (q1q3 + q0q2); hy = 2 * mx * (q1q2 + q0q3) + 2 * my * (0.5f - q1q1 - q3q3) + 2 * mz * (q2q3 - q0q1); - hz = 2 * mx * (q1q3 - q0q2) + 2 * my * (q2q3 + q0q1) + 2 * mz * (0.5f - q1q1 - q2q2); + hz = 2 * mx * (q1q3 - q0q2) + 2 * my * (q2q3 + q0q1) + 2 * mz * (0.5f - q1q1 - q2q2); bx = sqrt((hx * hx) + (hy * hy)); - bz = hz; + bz = hz; // estimated direction of gravity and flux (v and w) vx = 2 * (q1q3 - q0q2); @@ -144,7 +144,7 @@ void imuAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, f vz = q0q0 - q1q1 - q2q2 + q3q3; wx = 2 * bx * (0.5 - q2q2 - q3q3) + 2 * bz * (q1q3 - q0q2); wy = 2 * bx * (q1q2 - q0q3) + 2 * bz * (q0q1 + q2q3); - wz = 2 * bx * (q0q2 + q1q3) + 2 * bz * (0.5 - q1q1 - q2q2); + wz = 2 * bx * (q0q2 + q1q3) + 2 * bz * (0.5 - q1q1 - q2q2); // error is sum of cross product between reference direction of fields and direction measured by sensors ex = (ay * vz - az * vy) + (my * wz - mz * wy); @@ -154,7 +154,7 @@ void imuAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, f if(ex != 0.0f && ey != 0.0f && ez != 0.0f) { exInt = exInt + ex * Ki * halfT; - eyInt = eyInt + ey * Ki * halfT; + eyInt = eyInt + ey * Ki * halfT; ezInt = ezInt + ez * Ki * halfT; gx = gx + Kp * ex + exInt; @@ -165,7 +165,7 @@ void imuAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, f q0 = q0 + (-q1 * gx - q2 * gy - q3 * gz) * halfT; q1 = q1 + (q0 * gx + q2 * gz - q3 * gy) * halfT; q2 = q2 + (q0 * gy - q1 * gz + q3 * gx) * halfT; - q3 = q3 + (q0 * gz + q1 * gy - q2 * gx) * halfT; + q3 = q3 + (q0 * gz + q1 * gy - q2 * gx) * halfT; norm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); q0 = q0 * norm; @@ -174,16 +174,16 @@ void imuAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, f q3 = q3 * norm; } -float invSqrt(float x) +float invSqrt(float x) { float halfx = 0.5f * x; float y = x; - + long i = *(long*)&y; //get bits for floating value i = 0x5f3759df - (i >> 1); //gives initial guss you y = *(float*)&i; //convert bits back to float y = y * (1.5f - (halfx * y * y)); //newtop step, repeating increases accuracy - + return y; } @@ -197,7 +197,7 @@ void calibrateMagn(void) temp[0] = x; temp[1] = y; temp[2] = z; - + Serial.printf("rotate z axis 180 degrees and it will read all axises offset value after 4 seconds\n"); delay(4000); Serial.printf("start read all axises offset value\n"); diff --git a/General_Driver/RoArm-M2_module.h b/General_Driver/RoArm-M2_module.h index 7ff0a04..beb50fa 100644 --- a/General_Driver/RoArm-M2_module.h +++ b/General_Driver/RoArm-M2_module.h @@ -146,14 +146,14 @@ void setMiddlePos(byte InputID){ // to release all servos' torque for 10s. void emergencyStopProcessing() { st.EnableTorque(254, 0); - + } // position check. // it will wait for the servo to move to the goal position. void waitMove2Goal(byte InputID, s16 goalPosition, s16 offSet){ - while(servoFeedback[InputID - 11].pos < goalPosition - offSet || + while(servoFeedback[InputID - 11].pos < goalPosition - offSet || servoFeedback[InputID - 11].pos > goalPosition + offSet){ if (!servoFeedback[InputID - 11].status) { servoTorqueCtrl(254, 0); @@ -199,7 +199,7 @@ void RoArmM2_initCheck(bool returnType) { bool setServosPID(byte InputID, byte InputP) { if(!getFeedback(InputID, true)){return false;} st.unLockEprom(InputID); - st.writeByte(InputID, ST_PID_P_ADDR, InputP); + st.writeByte(InputID, ST_PID_P_ADDR, InputP); st.LockEprom(InputID); return true; } @@ -289,7 +289,7 @@ int RoArmM2_shoulderJointCtrlRad(byte returnType, double radInput, u16 speedInpu s16 computePos = calculatePosByRad(radInput); goalPos[1] = ARM_SERVO_MIDDLE_POS + computePos; goalPos[2] = ARM_SERVO_MIDDLE_POS - computePos; - + if(returnType == 1){ st.WritePosEx(SHOULDER_DRIVING_SERVO_ID, goalPos[1], speedInput, accInput); st.WritePosEx(SHOULDER_DRIVEN_SERVO_ID, goalPos[2], speedInput, accInput); @@ -327,7 +327,7 @@ int RoArmM2_elbowJointCtrlRad(byte returnType, double radInput, u16 speedInput, // servo will NOT move. // 1: returns the hand joint servo position and save it to goalPos[4], // servo moves. -// ctrl type 0: status ctrl. - cmd 0: release +// ctrl type 0: status ctrl. - cmd 0: release // 1: grab // 1: position ctrl. - cmd: input angle in radius. int RoArmM2_handJointCtrlRad(byte returnType, double radInput, u16 speedInput, u8 accInput) { @@ -379,7 +379,7 @@ void RoArmM2_handTorqueCtrl(int inputTorque) { // dynamic external force adaptation. // mode: 0 - stop: reset every limit torque to 1000. -// 1 - start: set the joint limit torque. +// 1 - start: set the joint limit torque. // b, s, e, h = bassJoint, shoulderJoint, elbowJoint, handJoint // example: // starts. input the limit torque of every joint. @@ -402,12 +402,12 @@ void RoArmM2_dynamicAdaptation(byte inputM, int inputB, int inputS, int inputE, // this function uses relative radInput to set a new X+ axis. -// dirInput: +// dirInput: // 0 // X+ // -90 - ^ - 90 // | -// -180 180 +// -180 180 void setNewAxisX(double angleInput) { double radInput = (angleInput / 180) * M_PI; RoArmM2_shoulderJointCtrlRad(1, 0, 500, 20); @@ -485,12 +485,12 @@ void simpleLinkageIkRad(double LA, double LB, double aIn, double bIn) { // ''' // AI prompt: -// I need a C language function. In a 2D Cartesian coordinate system, +// I need a C language function. In a 2D Cartesian coordinate system, // input a coordinate point (x, y). The function should return two values: // The distance from this coordinate point to the origin of the coordinate system. -// The angle, in radians, between the line connecting this point and the origin -// of the coordinate system and the positive direction of the x-axis. +// The angle, in radians, between the line connecting this point and the origin +// of the coordinate system and the positive direction of the x-axis. // The angle should be in the range (-π, π). void cartesian_to_polar(double x, double y, double* r, double* theta) { *r = sqrt(x * x + y * y); @@ -530,7 +530,7 @@ void RoArmM2_computePosbyJointRad(double base_joint_rad, double shoulder_joint_r r_ee = aOut + cOut; z_ee = bOut + dOut; - + polarToCartesian(r_ee, base_joint_rad, eOut, fOut); x_ee = eOut; y_ee = fOut; @@ -612,7 +612,7 @@ void RoArmM2_infoFeedback() { // AI prompt: // In a 2D Cartesian coordinate system, there is a point A. // Input the X and Y coordinates of point A and an angle parameter theta (in radians). -// Point A rotates counterclockwise around the origin of the Cartesian coordinate +// Point A rotates counterclockwise around the origin of the Cartesian coordinate // system by an angle of theta to become point B. Return the XY coordinates of point B. // I need a C language function. void rotatePoint(double theta, double *xB, double *yB) { @@ -627,9 +627,9 @@ void rotatePoint(double theta, double *xB, double *yB) { // 在平面直角坐标系种,有一点A,输入点A的X,Y坐标值,输入一个距离参数S, // 点A向原点方向移动S作为点B,返回点B的坐标值。我需要C语言的函数。 void movePoint(double xA, double yA, double s, double *xB, double *yB) { - double distance = sqrt(pow(xA, 2) + pow(yA, 2)); + double distance = sqrt(pow(xA, 2) + pow(yA, 2)); if(distance - s <= 1e-6) { - *xB = 0; + *xB = 0; *yB = 0; } else { @@ -739,9 +739,9 @@ void RoArmM2_singleJointAbsCtrl(byte jointInput, double inputRad, u16 inputSpd, // // // -------L3------------O==L2B==O <- BASE_JOINT -// ^ -// <---X+--Z+ | -// | ELBOW_JOINT +// ^ +// <---X+--Z+ | +// | ELBOW_JOINT // Y+ // | // v @@ -765,7 +765,7 @@ void RoArmM2_allJointAbsCtrl(double inputBase, double inputShoulder, double inpu // ctrl the movement in a smooth way. // | .. <-numEnd // | . | -// | . +// | . // | . | // | . // | . | @@ -777,7 +777,7 @@ double besselCtrl(double numStart, double numEnd, double rateInput){ numOut = (numEnd - numStart)*((cos(rateInput*M_PI+M_PI)+1)/2) + numStart; return numOut; } - + // use this function to get the max deltaSteps. // get the max offset between [goal] and [last] position. @@ -894,8 +894,8 @@ void RoArmM2_allPosAbsBesselCtrl(double inputX, double inputY, double inputZ, do // ''' // 我需要一个函数,输入圆心坐标点、半径和比例,当比例从0到1变化时,函数输出的坐标点可以组成一个完整的圆。 // ''' -// I need a function that inputs the center coordinate point, -// radius and scale(t), and when the scale(t) changes from 0 to 1, +// I need a function that inputs the center coordinate point, +// radius and scale(t), and when the scale(t) changes from 0 to 1, // the coordinate points output by the function can form a complete circle. // ''' // @@ -1020,9 +1020,9 @@ void RoArmM2_singleJointAngleCtrl(byte jointInput, double inputAng, u16 inputSpd // // // -------L3------------O==L2B==O <- BASE_JOINT -// ^ -// <---X+--Z+ | -// | ELBOW_JOINT +// ^ +// <---X+--Z+ | +// | ELBOW_JOINT // Y+ // | // v @@ -1035,7 +1035,7 @@ void RoArmM2_allJointsAngleCtrl(double inputBase, double inputShoulder, double i ELBOW_JOINT_ANG = inputElbow; ELBOW_JOINT_RAD = ang2deg(inputElbow); - + EOAT_JOINT_ANG = inputHand; EOAT_JOINT_RAD = ang2deg(inputHand); diff --git a/General_Driver/json_cmd.h b/General_Driver/json_cmd.h index 1148bcf..a7ecb14 100644 --- a/General_Driver/json_cmd.h +++ b/General_Driver/json_cmd.h @@ -245,7 +245,7 @@ // dynamic external force adaptation. // mode: 0 - stop: reset every limit torque to 1000. -// 1 - start: set the joint limit torque. +// 1 - start: set the joint limit torque. // b, s, e, h = bassJoint, shoulderJoint, elbowJoint, handJoint // example: // starts. input the limit torque of every joint. @@ -348,7 +348,7 @@ // === === === mission & steps edit. === === === -// create a mission in flash: +// create a mission in flash: // {"T":220,"name":"mission_a","intro":"test mission created in flash."} #define CMD_CREATE_MISSION 220 @@ -524,11 +524,11 @@ #define CMD_SET_SERVO_ID 501 // set the current position as the middle position. -// > BASE_SERVO_ID 11 -// > SHOULDER_DRIVING_SERVO_ID 12 -// > SHOULDER_DRIVEN_SERVO_ID 13 -// > ELBOW_SERVO_ID 14 -// > GRIPPER_SERVO_ID 15 +// > BASE_SERVO_ID 11 +// > SHOULDER_DRIVING_SERVO_ID 12 +// > SHOULDER_DRIVEN_SERVO_ID 13 +// > ELBOW_SERVO_ID 14 +// > GRIPPER_SERVO_ID 15 // {"T":502,"id":11} #define CMD_SET_MIDDLE 502 diff --git a/General_Driver/movtion_module.h b/General_Driver/movtion_module.h index 968664d..6f26d71 100644 --- a/General_Driver/movtion_module.h +++ b/General_Driver/movtion_module.h @@ -54,8 +54,8 @@ void switchPortCtrlA(float pwmInputA){ digitalWrite(AIN2, LOW); ledcWrite(channel_A,-pwmIntA); } -} +} void switchPortCtrlB(float pwmInputB){ int pwmIntB = round(pwmInputB * spd_rate_B); @@ -301,7 +301,7 @@ void setGoalSpeed(float inputLeft, float inputRight) { if(inputRight < -2.0 || inputRight > 2.0){ return; } - + setpointA = inputLeft*spd_rate_A; setpointB = inputRight*spd_rate_B; @@ -309,7 +309,7 @@ void setGoalSpeed(float inputLeft, float inputRight) { pidA.Setpoint(setpointA); setpointA_buffer = inputLeft; } - + if (setpointB != setpointB_buffer) { pidB.Setpoint(setpointB); setpointB_buffer = inputRight; @@ -437,7 +437,7 @@ void mm_settings(byte inputMain, byte inputModule) { screenLine_2 = "UGV02"; } else if (mainType == 3) { screenLine_2 = "UGV01"; - } + } if (moduleType == 0) { screenLine_2 += " Null"; @@ -445,5 +445,5 @@ void mm_settings(byte inputMain, byte inputModule) { screenLine_2 += " Arm"; } else if (moduleType == 2) { screenLine_2 += " PT"; - } + } } \ No newline at end of file diff --git a/General_Driver/oled_ctrl.h b/General_Driver/oled_ctrl.h index 2e9110d..9bdfaf5 100644 --- a/General_Driver/oled_ctrl.h +++ b/General_Driver/oled_ctrl.h @@ -65,7 +65,7 @@ void oledInfoUpdate() { // inaDataUpdate(); screenLine_3 = "V:"+String(loadVoltage_V); oled_update(); - + } // oled ctrl. diff --git a/General_Driver/uart_ctrl.h b/General_Driver/uart_ctrl.h index 20ebe8c..e78dd57 100644 --- a/General_Driver/uart_ctrl.h +++ b/General_Driver/uart_ctrl.h @@ -298,7 +298,7 @@ void jsonCmdReceiveHandler(){ missionContent( jsonCmdReceive["name"] );break; - case CMD_APPEND_STEP_JSON: + case CMD_APPEND_STEP_JSON: appendStepJson( jsonCmdReceive["name"], jsonCmdReceive["step"] @@ -377,7 +377,7 @@ void jsonCmdReceiveHandler(){ changeEspNowMode( jsonCmdReceive["mode"] );break; - case CMD_GET_MAC_ADDRESS: + case CMD_GET_MAC_ADDRESS: getThisDevMacAddress(); break; case CMD_ESP_NOW_ADD_FOLLOWER: @@ -411,7 +411,7 @@ void jsonCmdReceiveHandler(){ // wifi settings. - case CMD_WIFI_ON_BOOT: + case CMD_WIFI_ON_BOOT: configWifiModeOnBoot( jsonCmdReceive["cmd"] );break; @@ -430,9 +430,9 @@ void jsonCmdReceiveHandler(){ jsonCmdReceive["sta_password"] );break; case CMD_WIFI_INFO: wifiStatusFeedback();break; - case CMD_WIFI_CONFIG_CREATE_BY_STATUS: + case CMD_WIFI_CONFIG_CREATE_BY_STATUS: createWifiConfigFileByStatus();break; - case CMD_WIFI_CONFIG_CREATE_BY_INPUT: + case CMD_WIFI_CONFIG_CREATE_BY_INPUT: createWifiConfigFileByInput( jsonCmdReceive["mode"], jsonCmdReceive["ap_ssid"], diff --git a/General_Driver/ugv_config.h b/General_Driver/ugv_config.h index f59a8b4..46029da 100644 --- a/General_Driver/ugv_config.h +++ b/General_Driver/ugv_config.h @@ -84,7 +84,7 @@ String thisMacStr; #define ARM_L1_LENGTH_MM 126.06 #define ARM_L2_LENGTH_MM_A 236.82 -#define ARM_L2_LENGTH_MM_B 30.00 +#define ARM_L2_LENGTH_MM_B 30.00 #define ARM_L3_LENGTH_MM_A_0 280.15 #define ARM_L3_LENGTH_MM_B_0 1.73 @@ -218,7 +218,7 @@ bool nanIK; bool RoArmM2_initCheckSucceed = false; // bool RoArmM2_initCheckSucceed = true; -// // // args for syncWritePos. +// args for syncWritePos. u8 servoID[5] = {11, 12, 13, 14, 15}; s16 goalPos[5] = {2047, 2047, 2047, 2047, 2047}; u16 moveSpd[5] = {0, 0, 0, 0, 0}; diff --git a/General_Driver/web_page.h b/General_Driver/web_page.h index e4b0ad7..e114cb5 100644 --- a/General_Driver/web_page.h +++ b/General_Driver/web_page.h @@ -33,7 +33,7 @@ const char index_html[] PROGMEM = R"rawliteral( -khtml-user-select: none; -moz-user-select: none; -ms-user-select: none; - user-select: none; + user-select: none; } .cc-middle{ width: 100px; @@ -49,7 +49,7 @@ const char index_html[] PROGMEM = R"rawliteral( } .controlor-c > div{ width: 300px; - height: 300px; + height: 300px; background-color: rgba(94,98,112,0.2); border-radius: 40px; box-shadow: 10px 10px 10px rgba(0,0,0,0.05); diff --git a/General_Driver/wifi_ctrl.h b/General_Driver/wifi_ctrl.h index 9901101..a73e9dc 100644 --- a/General_Driver/wifi_ctrl.h +++ b/General_Driver/wifi_ctrl.h @@ -46,7 +46,7 @@ bool wifiConfigFound = false; // update oled accroding to wifi settings. void updateOledWifiInfo() { switch(WIFI_CURRENT_MODE) { - case 0: + case 0: screenLine_0 = "AP: OFF"; screenLine_1 = "ST: OFF"; break; @@ -73,7 +73,7 @@ bool loadWifiConfig() { wifiConfigYaml = LittleFS.open("/wifiConfig.json", "r"); if (wifiConfigYaml) { if (InfoPrint == 1) {Serial.println("/wifiConfig.json load succeed.");} - + String line = wifiConfigYaml.readStringUntil('\n'); // parse the YAML file using ArduinoJson. @@ -265,7 +265,7 @@ bool wifiModeAPSTA(const char* input_ap_ssid, const char* input_ap_password, con } ap_ssid = input_ap_ssid; ap_password = input_ap_password; - + WiFi.begin(input_sta_ssid, input_sta_password); connectionStartTime = millis(); @@ -309,7 +309,7 @@ bool wifiModeAPSTA(const char* input_ap_ssid, const char* input_ap_password, con jsonInfoHttp["sta_password"] = sta_password; jsonInfoHttp["ap_ssid"] = ap_ssid; jsonInfoHttp["ap_password"] = ap_password; - + return true; } @@ -327,7 +327,7 @@ void wifiStop() { bool wifiModeOnBoot() { bool funcStatus = false; switch(WIFI_MODE_ON_BOOT) { - case 0: + case 0: if (InfoPrint == 1) { Serial.println("wifi mode on boot: OFF"); } From a486bf4777d891320538f7e735fd5546f19e20ac Mon Sep 17 00:00:00 2001 From: Kerim Satirli Date: Tue, 30 Jul 2024 16:39:37 +0200 Subject: [PATCH 2/5] extraneous whitespace linting --- General_Driver/IMU.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/General_Driver/IMU.cpp b/General_Driver/IMU.cpp index 974858c..d4f68c6 100644 --- a/General_Driver/IMU.cpp +++ b/General_Driver/IMU.cpp @@ -89,7 +89,7 @@ void imuDataGet(EulerAngles *pstAngles, pstAngles->pitch = asin(-2 * q1 * q3 + 2 * q0* q2)* 57.3; // pitch pstAngles->roll = atan2(2 * q2 * q3 + 2 * q0 * q1, -2 * q1 * q1 - 2 * q2* q2 + 1)* 57.3; // roll - pstAngles->yaw = atan2(-2 * q1 * q2 - 2 * q0 * q3, 2 * q2 * q2 + 2 * q3 * q3 - 1) * 57.3; + pstAngles->yaw = atan2(-2 * q1 * q2 - 2 * q0 * q3, 2 * q2 * q2 + 2 * q3 * q3 - 1) * 57.3; pstGyroRawData->X = gyro[0]; pstGyroRawData->Y = gyro[1]; @@ -102,7 +102,7 @@ void imuDataGet(EulerAngles *pstAngles, return; } -void imuAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz) +void imuAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz) { float norm; float hx, hy, hz, bx, bz; From bbac349e432980eb441e0e3fc6a4a1d85f2451e5 Mon Sep 17 00:00:00 2001 From: Kerim Satirli Date: Tue, 30 Jul 2024 16:43:19 +0200 Subject: [PATCH 3/5] typograhical fixes --- General_Driver/General_Driver.ino | 2 +- General_Driver/RoArm-M2_module.h | 8 ++++---- General_Driver/json_cmd.h | 6 +++--- General_Driver/oled_ctrl.h | 2 +- General_Driver/ugv_config.h | 4 ++-- General_Driver/web_page.h | 8 ++++---- General_Driver/wifi_ctrl.h | 4 ++-- 7 files changed, 17 insertions(+), 17 deletions(-) diff --git a/General_Driver/General_Driver.ino b/General_Driver/General_Driver.ino index eb164b6..e8ba219 100644 --- a/General_Driver/General_Driver.ino +++ b/General_Driver/General_Driver.ino @@ -24,7 +24,7 @@ StaticJsonDocument<512> jsonInfoHttp; #include -// functions for barrery info. +// functions for battery info. #include "battery_ctrl.h" // functions for oled. diff --git a/General_Driver/RoArm-M2_module.h b/General_Driver/RoArm-M2_module.h index beb50fa..0530f95 100644 --- a/General_Driver/RoArm-M2_module.h +++ b/General_Driver/RoArm-M2_module.h @@ -137,7 +137,7 @@ void servoTorqueCtrl(byte servoID, u8 enableCMD){ // set the current position as the middle position of the servo. -// input the ID of the servo that you wannna set middle position. +// input the ID of the servo that you want to set middle position. void setMiddlePos(byte InputID){ st.CalibrationOfs(InputID); } @@ -165,7 +165,7 @@ void waitMove2Goal(byte InputID, s16 goalPosition, s16 offSet){ } -// initialize bus servo libraris and uart2ttl. +// initialize bus servo libraries and uart2ttl. void RoArmM2_servoInit(){ Serial1.begin(1000000, SERIAL_8N1, S_RXD, S_TXD); st.pSerial = &Serial1; @@ -276,7 +276,7 @@ int RoArmM2_baseJointCtrlRad(byte returnType, double radInput, u16 speedInput, u } -// use this function to compute the servo position to ctrl shoudlder joint. +// use this function to compute the servo position to ctrl shoulder joint. // returnType 0: only returns the shoulder joint servo position and save it to goalPos[1] and goalPos[2], // servo will NOT move. // 1: returns the shoulder joint servo position and save it to goalPos[1] and goalPos[2], @@ -506,7 +506,7 @@ void cartesian_to_polar(double x, double y, double* r, double* theta) { // 你在回答的过程中可以告诉我你还有什么其它需要的信息。 // ''' // use this two functions to compute the position of coordinate point -// by inputing the jointRad. +// by inputting the jointRad. // 这个函数用于将极坐标转换为直角坐标 void polarToCartesian(double r, double theta, double &x, double &y) { x = r * cos(theta); diff --git a/General_Driver/json_cmd.h b/General_Driver/json_cmd.h index a7ecb14..706e7fb 100644 --- a/General_Driver/json_cmd.h +++ b/General_Driver/json_cmd.h @@ -109,7 +109,7 @@ // {"T":142,"cmd":0} #define CMD_FEEDBACK_FLOW_INTERVAL 142 // dev -// set the echo mode of recving new cmd. +// set the echo mode of receiving new cmd. // 0: [default]off // 1: on // {"T":143,"cmd":0} @@ -425,9 +425,9 @@ // === === === ESP-NOW settings. === === === // note: wifi must be running under STA(AP+STA) mode. -// it will be controled by broadcast mac address. +// it will be controlled by broadcast mac address. // {"T":300,"mode":1} [default] -// it won't be controled by broadcast mac address, and add one mac to whitelist. +// it won't be controlled by broadcast mac address, and add one mac to whitelist. // if there is no leader you can just fill 00:00:00:00:00:00 in it. // {"T":300,"mode":0,"mac":"CC:DB:A7:5B:E4:1C"} #define CMD_BROADCAST_FOLLOWER 300 diff --git a/General_Driver/oled_ctrl.h b/General_Driver/oled_ctrl.h index 9bdfaf5..0b9db98 100644 --- a/General_Driver/oled_ctrl.h +++ b/General_Driver/oled_ctrl.h @@ -37,7 +37,7 @@ void init_oled(){ } -// Updata all data and flash the screen. +// Update all data and flash the screen. void oled_update() { display.clearDisplay(); display.setCursor(0,0); diff --git a/General_Driver/ugv_config.h b/General_Driver/ugv_config.h index 46029da..c90edc4 100644 --- a/General_Driver/ugv_config.h +++ b/General_Driver/ugv_config.h @@ -17,8 +17,8 @@ byte espNowMode = 3; // set the broadcast ctrl mode. // broadcast mac address: FF:FF:FF:FF:FF:FF. -// true - [default]it can be controled by broadcast mac address. -// false - it won't be controled by broadcast mac address. +// true - [default]it can be controlled by broadcast mac address. +// false - it won't be controlled by broadcast mac address. bool ctrlByBroadcast = true; // you can define some whitelist mac addresses here. diff --git a/General_Driver/web_page.h b/General_Driver/web_page.h index e114cb5..5a244f9 100644 --- a/General_Driver/web_page.h +++ b/General_Driver/web_page.h @@ -338,7 +338,7 @@ const char index_html[] PROGMEM = R"rawliteral(
- +
@@ -378,12 +378,12 @@ const char index_html[] PROGMEM = R"rawliteral(
-

Feedback infomation

- Json feedback infomation shows here. +

Feedback information

+ JSON feedback information shows here.
- +
diff --git a/General_Driver/wifi_ctrl.h b/General_Driver/wifi_ctrl.h index a73e9dc..8d6c9f5 100644 --- a/General_Driver/wifi_ctrl.h +++ b/General_Driver/wifi_ctrl.h @@ -43,7 +43,7 @@ DynamicJsonDocument wifiDoc(256); bool wifiConfigFound = false; -// update oled accroding to wifi settings. +// update OLED according to wifi settings. void updateOledWifiInfo() { switch(WIFI_CURRENT_MODE) { case 0: @@ -102,7 +102,7 @@ bool loadWifiConfig() { return true; } else { - if (InfoPrint == 1) {Serial.println("cound not found wifiConfig.json.");} + if (InfoPrint == 1) {Serial.println("could not found wifiConfig.json.");} wifiConfigFound = false; return false; } From 914859124b30ab4b3d0f03db029e1c8baa5f0af0 Mon Sep 17 00:00:00 2001 From: Kerim Satirli Date: Tue, 30 Jul 2024 16:43:36 +0200 Subject: [PATCH 4/5] corrects mimetype --- General_Driver/http_server.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/General_Driver/http_server.h b/General_Driver/http_server.h index 2ec6463..417d926 100644 --- a/General_Driver/http_server.h +++ b/General_Driver/http_server.h @@ -15,7 +15,7 @@ void webCtrlServer(){ deserializeJson(jsonCmdReceive, jsonCmdWebString); jsonCmdReceiveHandler(); serializeJson(jsonInfoHttp, jsonFeedbackWeb); - server.send(200, "text/plane", jsonFeedbackWeb); + server.send(200, "text/json", jsonFeedbackWeb); jsonFeedbackWeb = ""; jsonInfoHttp.clear(); jsonCmdReceive.clear(); From 8fa8bd548bfc3bc7b83c2d88ee759ffeb06175ed Mon Sep 17 00:00:00 2001 From: Kerim Satirli Date: Wed, 31 Jul 2024 11:19:44 +0200 Subject: [PATCH 5/5] more typo fixes --- General_Driver/AK09918.h | 2 +- General_Driver/RoArm-M2_module.h | 10 +++++----- General_Driver/esp_now_ctrl.h | 2 +- General_Driver/json_cmd.h | 2 +- 4 files changed, 8 insertions(+), 8 deletions(-) diff --git a/General_Driver/AK09918.h b/General_Driver/AK09918.h index 49deaf3..1b78c64 100644 --- a/General_Driver/AK09918.h +++ b/General_Driver/AK09918.h @@ -66,7 +66,7 @@ #define AK09918_DRDY_BIT 0x01 // Data Ready // #define AK09918_MEASURE_PERIOD 9 // Must not be changed -// AK09918 has following seven operation modes: +// AK09918 has the following seven operation modes: // (1) Power-down mode: AK09918 doesn't measure // (2) Single measurement mode: measure when you call any getData() function // (3) Continuous measurement mode 1: 10Hz, measure 10 times per second, diff --git a/General_Driver/RoArm-M2_module.h b/General_Driver/RoArm-M2_module.h index 0530f95..02f0e5a 100644 --- a/General_Driver/RoArm-M2_module.h +++ b/General_Driver/RoArm-M2_module.h @@ -226,7 +226,7 @@ void RoArmM2_moveInit() { if(InfoPrint == 1){Serial.println("Moving SHOULDER_JOINT to initPos.");} st.WritePosEx(SHOULDER_DRIVING_SERVO_ID, ARM_SERVO_MIDDLE_POS, ARM_SERVO_INIT_SPEED, ARM_SERVO_INIT_ACC); - // check SHOULDER_DRIVEING_SERVO position. + // check SHOULDER_DRIVING_SERVO_ID position. if(InfoPrint == 1){Serial.println("...");} waitMove2Goal(SHOULDER_DRIVING_SERVO_ID, ARM_SERVO_MIDDLE_POS, 30); @@ -516,7 +516,7 @@ void polarToCartesian(double r, double theta, double &x, double &y) { // this function is used to compute the position of the end point. // input the angle of every joint in radius. -// compute the positon and save it to lastXYZ by default. +// compute the position and save it to lastXYZ by default. void RoArmM2_computePosbyJointRad(double base_joint_rad, double shoulder_joint_rad, double elbow_joint_rad, double hand_joint_rad) { if (EEMode == 0) { // the end of the arm. @@ -640,10 +640,10 @@ void movePoint(double xA, double yA, double s, double *xB, double *yB) { } -// ---===< Muti-assembly IK config here >===--- +// ---===< Multi-assembly IK config here >===--- // change this func and goalPosMove() // Coordinate Ctrl: input the coordinate point of the goal position to compute -// the goalPos of every joints. +// the goalPos of every joint. void RoArmM2_baseCoordinateCtrl(double inputX, double inputY, double inputZ, double inputT){ if (EEMode == 0) { cartesian_to_polar(inputX, inputY, &base_r, &BASE_JOINT_RAD); @@ -671,7 +671,7 @@ void RoArmM2_lastPosUpdate(){ // use jointCtrlRad functions to compute goalPos for every servo, // then use this function to move the servos. -// cuz the functions like baseCoordinateCtrl is not gonna make servos move. +// because the functions like baseCoordinateCtrl is not going to make servos move. void RoArmM2_goalPosMove(){ RoArmM2_baseJointCtrlRad(0, BASE_JOINT_RAD, 0, 0); RoArmM2_shoulderJointCtrlRad(0, SHOULDER_JOINT_RAD, 0, 0); diff --git a/General_Driver/esp_now_ctrl.h b/General_Driver/esp_now_ctrl.h index 98b0500..e7d713a 100644 --- a/General_Driver/esp_now_ctrl.h +++ b/General_Driver/esp_now_ctrl.h @@ -188,7 +188,7 @@ void initEspNow() { // register esp-now sending call back function. esp_now_register_send_cb(OnDataSent); - // register esp-now receving call back function. + // register esp-now receiving call back function. esp_now_register_recv_cb(OnDataRecv); // register peer diff --git a/General_Driver/json_cmd.h b/General_Driver/json_cmd.h index 706e7fb..8bdeddb 100644 --- a/General_Driver/json_cmd.h +++ b/General_Driver/json_cmd.h @@ -88,7 +88,7 @@ // the robot need to be put on a ground and kept still // getting the imu offset and set as default -// this gonna take a while (5s) +// this is going to take a while (5s) // {"T":127} #define CMD_CALI_IMU_STEP 127