mc_client_interface.h 7.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158
  1. #ifndef MC_CLIENT_INTERFACE_H
  2. #define MC_CLIENT_INTERFACE_H
  3. #include <iostream>
  4. #include <memory>
  5. #include <string>
  6. #include <vector>
  7. #include "common.h"
  8. // extern "C" {
  9. using namespace robot_control;
  10. bool rcClientInterfaceInit(std::string target_ip);
  11. std::string rcClientInterfaceGetMcVersion(const int& index);
  12. std::string rcClientInterfaceGetRobotName(const int& index);
  13. bool rcClientInterfaceGetMcMoveStatus(int index, common::MC_QUATERNIONS *state_attribute);
  14. // imu 数据上报
  15. bool rcClientInterfaceGetImuData(common::MC_MOTION_IMU_DATA *imu_data);
  16. bool rcClientInterfaceGetImuStreamData(std::vector<common::MC_MOTION_IMU_DATA> *imu_data_list);
  17. // 坐下(默认)/起立
  18. bool rcClientInterfaceLieDownOrStandUp(robot_control::common::NAV_OR_JOY_MODE from,bool liedown_standup);
  19. // 使能
  20. bool rcClientInterfaceDriverEnable(robot_control::common::NAV_OR_JOY_MODE from, bool driver_enable);
  21. // 前进方向(前后左右)
  22. bool rcClientInterfaceDirectionMovement(robot_control::common::NAV_OR_JOY_MODE from,
  23. common::ROBOT_TWIST rc_direct, int64_t time_millis);
  24. // 步态
  25. bool rcClientInterfaceSetGait(robot_control::common::NAV_OR_JOY_MODE from, common::ROBOT_GAIT gain);
  26. // 高度调节条
  27. bool rcClientInterfaceBodyHighAdjust(robot_control::common::NAV_OR_JOY_MODE from, int scale);
  28. // 速度调节条
  29. bool rcClientInterfaceSpeedAdjust(robot_control::common::NAV_OR_JOY_MODE from, int scale);
  30. // 场景设定
  31. bool rcClientInterfaceSetScene(robot_control::common::NAV_OR_JOY_MODE from, common::SCENE_TYPE scene);
  32. // 机器人一键自恢复
  33. bool rcClientInterfaceSelfRecovery(robot_control::common::NAV_OR_JOY_MODE from);
  34. // 力矩传感器清零
  35. bool rcClientInterfaceZeroTorqueSensor(robot_control::common::NAV_OR_JOY_MODE from);
  36. // 机器人常规状态信息
  37. bool rcClientInterfaceGetCommonStatus(common::ROBOT_COMMON_STATUS *com_state);
  38. // 机器人本体状态信息
  39. bool rcClientInterfaceGetJointsStatus(common::ROBOT_JOINTS_STATUS *state);
  40. // 机器人日志信息
  41. bool rcClientInterfaceLogUpdate(std::vector<std::string> &log_list);
  42. bool rcClientInterfaceSetJoyKeyValues(common::JOY_KEY_TYPE joy_key_attribute);
  43. // 遥控或手柄控制模式
  44. bool rcClientInterfaceDriverEstop(robot_control::common::NAV_OR_JOY_MODE from);
  45. // 遥控或手柄控制模式
  46. bool rcClientInterfaceResumeEstop(robot_control::common::NAV_OR_JOY_MODE from);
  47. // 软件急停
  48. bool rcClientInterfaceDriverSoftEstop(robot_control::common::NAV_OR_JOY_MODE from);
  49. // 恢复软件急停
  50. bool rcClientInterfacercResumeSoftEstop(robot_control::common::NAV_OR_JOY_MODE from);
  51. // 自动充电
  52. bool rcClientInterfaceSetAutoCharge(
  53. robot_control::common::NAV_OR_JOY_MODE from,
  54. common::AUTO_CHARGE_STATE charge_state);
  55. // 设置导航控制或者遥控控制
  56. bool rcClientInterfaceSetNavOrJoyControl(
  57. common::NAV_OR_JOY_MODE nav_joy);
  58. // 设置机器人位姿
  59. bool rcClientInterfaceSetPoseEstimate(
  60. robot_control::common::NAV_OR_JOY_MODE from,
  61. common::ROBOT_POSE_ESTIMATE estimate);
  62. // 机器人充电识别二维码
  63. bool rcClientInterfaceIdentifyQRCode(robot_control::common::NAV_OR_JOY_MODE from);
  64. bool rcClientInterfaceEnterOrExitCharge(
  65. robot_control::common::NAV_OR_JOY_MODE from,
  66. bool driver_enable);
  67. bool rcClientInterfaceAutoRechargeCmd(
  68. robot_control::common::NAV_OR_JOY_MODE from,
  69. common::JETSON_CHARGE_COMMAND charge_command);
  70. bool rcClientInterfaceGetChargeState(common::JETSON_CHARGE_STATE *charge_state);
  71. bool rcClientInterfaceLightStripControl(
  72. robot_control::common::NAV_OR_JOY_MODE from,
  73. std::string port, EN_MICRO_EMOJI_CONTROL_CMD cmd,
  74. int deviceAddr, int data);
  75. bool rcClientInterfaceSerialControl(
  76. robot_control::common::NAV_OR_JOY_MODE from,
  77. std::string port, std::string raw_data);
  78. bool rcClientInterfaceSetGuardian(
  79. common::NAV_OR_JOY_MODE from,
  80. float velocity_decay_ratio,
  81. std::string trigger_source);
  82. bool rcClientInterfaceSetGuardianSwitch(
  83. robot_control::common::NAV_OR_JOY_MODE from,
  84. bool enable);
  85. bool rcClientInterfaceSetVisualFootholdSwitch(
  86. robot_control::common::NAV_OR_JOY_MODE from,
  87. bool enable);
  88. bool rcClientInterfaceSetVisualFootholdCommand(
  89. common::JETSON_VISUAL_FOOTHOLD_COMMAND map);
  90. bool rcClientInterfaceGetVisualFootholdState(
  91. common::JETSON_VISUAL_FOOTHOLD_STATE *foothold_state);
  92. bool rcClientInterfaceGetDepthImage(
  93. common::DEPTH_IMAGE *depth_image);
  94. bool rcClientInterfaceGetRgbImage(
  95. common::RGB_IMAGE *rgb_image);
  96. bool rcClientInterfaceGetMotionControllerTimestamp(unsigned long *timestamp);
  97. bool rcClientInterfaceSetNavigationPositioningState(
  98. common::NAV_OR_JOY_MODE from,
  99. bool enable);
  100. bool rcClientInterfaceSetNavigationInitialPos(
  101. common::NAV_OR_JOY_MODE from,
  102. bool enable);
  103. bool rcClientInterfaceSetTerrainSegDetectionResults(
  104. common::NAV_OR_JOY_MODE from,
  105. common::TERRAIN_SEG_DETECTION_RESULTS terrain);
  106. bool rcClientInterfaceSetTargetBodyOrientation(
  107. common::NAV_OR_JOY_MODE from,
  108. float roll, float pitch, float yaw);
  109. bool rcClientInterfaceSetEQAState(
  110. common::NAV_OR_JOY_MODE from,
  111. common::EQA_STATE eqa_state);
  112. bool rcClientInterfaceSetStairsHeigh(
  113. common::NAV_OR_JOY_MODE from,
  114. common::STAIRS_HEIGH_STATE stairs_heigh_value);
  115. bool rcClientInterfaceSetUWBFunctionSwitch(
  116. common::NAV_OR_JOY_MODE from,
  117. bool enable);
  118. bool rcClientInterfaceSetWeightLoadAdaptive(
  119. common::NAV_OR_JOY_MODE from,
  120. bool enable);
  121. ////////////////////////////
  122. bool rcClientInterfaceGetLatestError(std::string* error_code);
  123. bool rcClientInterfaceGetHistoryError(int* error_count, std::vector<std::string>& error_codes);
  124. bool rcClientInterfaceGetNavigationPositioningState(bool* state);
  125. bool rcClientInterfaceGetNavigationInitialPos(bool* init);
  126. bool rcClientInterfaceGetEQAState(robot_control::common::EQA_STATE *eqa_state);
  127. bool rcClientInterfaceDemoControl(
  128. common::NAV_OR_JOY_MODE from,
  129. int mode,
  130. bool enable);
  131. bool rcClientInterfaceSetJointsMode(int mode);
  132. bool rcClientInterfaceSetJointsPVQ(common::ROBOT_TARGET_VALUE value);
  133. bool rcClientInterfaceGetJointsPVQ(common::ROBOT_TARGET_VALUE *value);
  134. bool rcClientInterfaceDriverParameterSetting(
  135. robot_control::common::NAV_OR_JOY_MODE from,
  136. int motor_index, int which_core_of_driver,
  137. DRIVER_PARAM_SETTING_CMD cmd);
  138. bool rcClientInterfaceSetFormOfMovement(int mode);
  139. bool rcClientInterfaceSelectSomeJoints(unsigned int mask);
  140. bool rcClientInterfaceSelectSingleJoint(int axis_index, bool be_selected);
  141. bool rcClientInterfaceClearDriverError(unsigned int mask);
  142. bool rcClientInterfaceSetMaxTorqueLimit(int axis_index, double max_torque);
  143. bool rcClientInterfaceReCalibrateAllDriverAndSave(bool is_rough);
  144. bool rcClientInterfaceSetJointTestParameter (common::JointTestData joint_test_data);
  145. bool rcClientInterfaceSineMoveJointTestSwitch (bool be_enable);
  146. bool rcClientInterfaceQuitJointTest ();
  147. bool rcClientInterfaceClearErrorHistory(common::NAV_OR_JOY_MODE from);
  148. bool rcClientInterfaceClearLatestHistory(common::NAV_OR_JOY_MODE from);
  149. // }
  150. #endif // MC_CLIENT_INTERFACE_H