瀏覽代碼

fix: update mc_client_sdk to fix issues

zhanghy64 5 月之前
父節點
當前提交
4247180ded

+ 11 - 3
saturn_controller/sdk/include/com_define.h

@@ -32,7 +32,7 @@
 
 #define MAX_ERROR_QUEUE_SIZE 200
 #define CODE_WHEEL_NUM 5
-#define JOINT_CODE_WHEEL_NUM 10
+#define JOINT_CODE_WHEEL_NUM 20
 
 typedef enum _DRIVE_MODE{
     POSITION_MODE = 0,
@@ -54,6 +54,8 @@ typedef enum _DRIVER_PARAM_SETTING_CMD{
     SET_ENCODER_POWER_14,
     SET_ENCODER_POWER,
     READ_DRIVER_STRING_STO_ERR,
+	DRIVER_FOE_UPDATE,
+	SET_ENCODER_ZERO_AND_SAVE,
     CMD_MAX
 }DRIVER_PARAM_SETTING_CMD;
 
@@ -123,11 +125,17 @@ typedef enum _EN_LAMP_EFFECT_THEME{
 	COLD_GREY_THEME = 2,
 }EN_LAMP_EFFECT_THEME;
 
-typedef enum _ROBORT_BODY_MODEL{
+typedef enum _ROBOT_DRIVER_TYPES{
 	GS_SYNAPTICON = 0,
 	IS_FORCE_POS_MIXING = 1,
 	IS_ONLY_FORCE = 2,
-}ROBORT_BODY_MODEL;
+}ROBOT_DRIVER_TYPES;
+
+typedef enum _ROBOT_BODY_TYPES{
+	NULL_TYPE = 0,
+	HEXAPOD = 1,
+	QUADRUPED = 2
+}ROBOT_BODY_TYPES;
 
 #define UNUSED(x) (void)(x)
 #define LOG_LENGTH 256

+ 12 - 8
saturn_controller/sdk/include/common.h

@@ -69,6 +69,10 @@ typedef union {
     } axis;
 } EulerAngleVector;
 
+typedef union{
+    double array[9];
+} Covariance;
+
 /**
  * @brief Quaternion.
  */
@@ -93,7 +97,7 @@ typedef union {
 
 typedef struct TOP_CONFIG_INFO_{
     std::string robot_type;
-    ROBORT_BODY_MODEL body_model;
+    ROBOT_DRIVER_TYPES body_model;
 }TOP_CONFIG_INFO;
 
 namespace robot_control
@@ -126,13 +130,15 @@ namespace robot_control
             GID_IDLE_GAIT  = 1,
             GID_STANDSTILL = 2,
             GID_RECOVER    = 3,
-            GID_NIMBLE     = 4,
+            GID_HEX_NIMBLE     = 4,
             GID_JOINT_TEST = 5,
             GID_RL  = 6, //强化学习步态
             GID_JOINT_TRAJECTORY_CONTROL  = 7,
             GID_POSE_ADJUSTMENT=8,
             GID_FOOT_ADJUST=9,
-            GID_LEG_TEST=10
+            GID_LEG_TEST=10,
+            GID_QUA_NIMBLE = 11,
+            GID_MAX = 12
         };
 
         class GaitMsgHeader
@@ -482,8 +488,6 @@ namespace robot_control
             TAI_JIE = 11
         }TERRAIN_SEG_DETECTION_RESULTS;
 
-        
-
         typedef struct ROBOT_COMMON_STATUS_{
             int network; //机器人当前网络状态
             BODY_POSTURE_STATE belie_or_stand; //机器人处于站立趴下状态(目前不用,芳勇认为测试中可能会用)
@@ -527,7 +531,7 @@ namespace robot_control
             float speed_bar_on_controller; //机器人遥控器上当前选中的线速度
             CALIBRATE_POSE_STATE calibrate_pos_state;
             int self_test_code;
-            bool encoder_calibrate_state;
+            int encoder_calibrate_state;
 
             bool nav_pos_state;//当前导航定位位置是否正常
             bool nav_init_pos;//是否尝试初始化导航定位
@@ -648,12 +652,12 @@ namespace robot_control
             EN_LAMP_EFFECT_THEME lamp_effect_theme;
         }ROBOT_SPECIAL_CONFIG_INFO;
 
-        typedef enum _ROBOT_BODY_TYPE{
+        typedef enum _ROBOT_WORKING_ENVIRINMENT{
             ROBOT_BODY_NON = 0,
             ROBOT_BODY_REAL,
             ROBOT_BODY_WEBOTS,
             ROBOT_BODY_GAZEBO
-        }ROBOT_BODY_TYPE;
+        }ROBOT_WORKING_ENVIRINMENT;
 
         typedef enum LOG_LEVEL_{
             LOG_LEVEL_NON = 0,

+ 14 - 4
saturn_controller/sdk/include/error_code.h

@@ -10,7 +10,12 @@
 #define RC_ERROR_DRIVER_NEED_POS_CALIBRATE_CODE         0x00000006
 #define RC_ERROR_BATTARY_LEVEL_IS_TOO_LOW_CODE          0x00000007
 #define RC_ERROR_DRIVER_ENCODER_HAS_BEEN_RESET_CODE          0x00000008
-#define RC_ERROR_CODE_CUR_MAX_INDEX                     0x00000009
+#define RC_ERROR_ROBOT_ESTOP_OCCURRED_CODE          0x00000009
+#define RC_ERROR_LIEDOWN_POSTURE_WITH_LEGS_PLACED_CODE               0x0000000A
+#define RC_ERROR_DRIVER_ENABLED_FAILED_WITHIN_DEADLINE_CODE               0x0000000B
+#define RC_ERROR_DRIVER_ENABLE_CANNOT_PASS_SELFCHECK_CODE              0x0000000C
+#define RC_ERROR_RUNTIME_BUS_NET_CANNOT_BUILD_CODE              0x0000000D
+#define RC_ERROR_CODE_CUR_MAX_INDEX                     0x0000000E
 
 #define RC_ERROR_MAX_INDEX_CODE                         (CODE_WHEEL_NUM * 32)
 
@@ -23,6 +28,11 @@
 #define RC_ERROR_DRIVER_NEED_POS_CALIBRATE_MSG  "The driver's position need calibrate after power on."
 #define RC_ERROR_BATTARY_LEVEL_IS_TOO_LOW_MSG        "The Robot's battary is too low, must estop!"
 #define RC_ERROR_DRIVER_ENCODER_HAS_BEEN_RESET_MSG        "The Dirver's Encoder has been reset. You need recalibrate the robot joint position!"
+#define RC_ERROR_ROBOT_ESTOP_OCCURRED_MSG       "The Robot has been EStoped!"
+#define RC_ERROR_LIEDOWN_POSTURE_WITH_LEGS_PLACED_MSG      "The Robot's lie down posture is not correct."
+#define RC_ERROR_DRIVER_ENABLED_FAILED_WITHIN_DEADLINE_MSG      "The Robot's can't completed driver enable within the deadline."
+#define RC_ERROR_DRIVER_ENABLE_CANNOT_PASS_SELFCHECK_MSG    "The Robot's can't pass self check, so driver can't be Enabled."
+#define RC_ERROR_RUNTIME_BUS_NET_CANNOT_BUILD_MSG      "The Robot's runtime bus net can't be build, please check line and slaves."
 
 
 #define RC_JOINT_ERROR_CLEAR_7303_FAILED_CODE          0x00000001
@@ -61,9 +71,9 @@
 #define RC_JOINT_ERROR_ENCODER_BATTERY_MSG       "Driver encoder battery 7303 error BisWnBit."
 #define RC_JOINT_ERROR_MOTOR_FAULT_OCCURED_MSG      "The motor has error. Please stop Robot."
 #define RC_JOINT_ERROR_DRIVER_FAULT_OCCURED_MSG      "The driver has error. Please stop Robot."
-#define RC_JOINT_ERROR_DRIVER_CPU_TEMPERATURE_TOO_HEIGH_MSG      "The driver's cpu temperature is too heigh. Please stop Robot."
-#define RC_JOINT_ERROR_DRIVER_TEMPERATURE_TOO_HEIGH_MSG      "The driver's temperature is too heigh. Please stop Robot."
-#define RC_JOINT_ERROR_MOTOR_TEMPERATURE_TOO_HEIGH_MSG      "The motor's temperature is too heigh. Please stop Robot."
+#define RC_JOINT_ERROR_DRIVER_CPU_TEMPERATURE_TOO_HEIGH_MSG      "The driver's cpu temperature is too high. Please stop Robot."
+#define RC_JOINT_ERROR_DRIVER_TEMPERATURE_TOO_HEIGH_MSG      "The driver's temperature is too high. Please stop Robot."
+#define RC_JOINT_ERROR_MOTOR_TEMPERATURE_TOO_HEIGH_MSG      "The motor's temperature is too high. Please stop Robot."
 
 
 

+ 7 - 2
saturn_controller/sdk/include/mc_client_interface.h

@@ -76,7 +76,11 @@ bool rcClientInterfaceAutoRechargeCmd(
 bool rcClientInterfaceGetChargeState(common::JETSON_CHARGE_STATE *charge_state);
 bool rcClientInterfaceLightStripControl(
             robot_control::common::NAV_OR_JOY_MODE from,
-            std::string port, EN_MICRO_EMOJI_CONTROL_CMD cmd, int deviceAddr, int data);
+            std::string port, EN_MICRO_EMOJI_CONTROL_CMD cmd,
+			int deviceAddr, int data);
+bool rcClientInterfaceSerialControl(
+            robot_control::common::NAV_OR_JOY_MODE from,
+            std::string port, std::string raw_data);
 bool rcClientInterfaceSetGuardian(
 			common::NAV_OR_JOY_MODE from,
 			float velocity_decay_ratio,
@@ -136,7 +140,7 @@ bool rcClientInterfaceSetJointsPVQ(common::ROBOT_TARGET_VALUE value);
 bool rcClientInterfaceGetJointsPVQ(common::ROBOT_TARGET_VALUE *value);
 bool rcClientInterfaceDriverParameterSetting(
             robot_control::common::NAV_OR_JOY_MODE from,
-            int motor_index,
+            int motor_index, int which_core_of_driver,
             DRIVER_PARAM_SETTING_CMD cmd);
 bool rcClientInterfaceSetFormOfMovement(int mode);
 bool rcClientInterfaceSelectSomeJoints(unsigned int mask);
@@ -148,6 +152,7 @@ bool rcClientInterfaceSetJointTestParameter (common::JointTestData joint_test_da
 bool rcClientInterfaceSineMoveJointTestSwitch (bool be_enable);
 bool rcClientInterfaceQuitJointTest ();
 bool rcClientInterfaceClearErrorHistory(common::NAV_OR_JOY_MODE from);
+bool rcClientInterfaceClearLatestHistory(common::NAV_OR_JOY_MODE from);
 
 // }
 #endif // MC_CLIENT_INTERFACE_H

二進制
saturn_controller/sdk/lib/arm/libmc_client.so


二進制
saturn_controller/sdk/lib/x86_64/libmc_client.so