|
@@ -183,24 +183,14 @@ void SaturnController::robotCommandCallback(
|
|
|
robot_control::common::CONTROL_SOURCE_MODE::nav_control, rc_direct,
|
|
|
robot_heartbeat_);
|
|
|
} else if ("StandUpDown" == request->comamnd_name) {
|
|
|
- // fangyong 后续站立趴下,可以直接判断BODY_POSTURE_STATE ROBOT_COMMON_STATUS里的belie_or_stand;
|
|
|
- SPDLOG_INFO("cur_scene {}", common_status_data_.cur_scene);
|
|
|
- if ((common_status_data_.cur_scene ==
|
|
|
- robot_control::common::SCENE_TYPE::WALKING) ||
|
|
|
- (common_status_data_.cur_scene ==
|
|
|
- robot_control::common::SCENE_TYPE::STAIRS) ||
|
|
|
- (common_status_data_.cur_scene ==
|
|
|
- robot_control::common::SCENE_TYPE::STONE) ||
|
|
|
- //fangyong 斜坡
|
|
|
- (common_status_data_.cur_scene ==
|
|
|
- robot_control::common::SCENE_TYPE::ROUGH) ||
|
|
|
- (common_status_data_.cur_scene ==
|
|
|
- robot_control::common::SCENE_TYPE::RL)) {
|
|
|
+ SPDLOG_INFO("stand or lie {}", common_status_data_.belie_or_stand);
|
|
|
+ if (common_status_data_.belie_or_stand ==
|
|
|
+ robot_control::common::BODY_POSTURE_STATE::STANDUP) {
|
|
|
result = rcClientInterfaceSetScene(
|
|
|
robot_control::common::CONTROL_SOURCE_MODE::nav_control,
|
|
|
common::SCENE_TYPE::LIE_DOWN);
|
|
|
- }
|
|
|
- else if (common_status_data_.cur_scene == robot_control::common::LIE_DOWN) {
|
|
|
+ } else if (common_status_data_.belie_or_stand ==
|
|
|
+ robot_control::common::BODY_POSTURE_STATE::LIEDOWN) {
|
|
|
result = rcClientInterfaceSetScene(
|
|
|
robot_control::common::CONTROL_SOURCE_MODE::nav_control,
|
|
|
common::SCENE_TYPE::WALKING);
|
|
@@ -253,7 +243,7 @@ void SaturnController::robotCommandCallback(
|
|
|
SPDLOG_INFO("SlopeGait is called");
|
|
|
result = rcClientInterfaceSetScene(
|
|
|
robot_control::common::CONTROL_SOURCE_MODE::nav_control,
|
|
|
- common::SCENE_TYPE::STONE); //fangyong 斜坡步态改为调用 common::SCENE_TYPE::ROUGH
|
|
|
+ common::SCENE_TYPE::ROUGH);
|
|
|
} else if ("VstairsGait" == request->comamnd_name) {
|
|
|
SPDLOG_WARN("VstairsGait is not supported yet.");
|
|
|
result = false;
|
|
@@ -480,7 +470,7 @@ void SaturnController::publishRobotState() { // todo 这里逻辑还不完善
|
|
|
break;
|
|
|
}
|
|
|
case SDK_SCENE_TYPE::WALKING:
|
|
|
- case SDK_SCENE_TYPE::STONE:
|
|
|
+ case SDK_SCENE_TYPE::ROUGH:
|
|
|
case SDK_SCENE_TYPE::PERCEIVE_STAIRS:
|
|
|
case SDK_SCENE_TYPE::SNOW:
|
|
|
case SDK_SCENE_TYPE::SLIPPY:
|
|
@@ -548,7 +538,7 @@ void SaturnController::publishControlMode() {
|
|
|
using SDK_CONTROL_MODE = robot_control::common::CONTROL_SOURCE_MODE;
|
|
|
auto curr_mode = CONTROL_MODE::NULL_MODE;
|
|
|
|
|
|
- switch (common_status_data_.joy_mode) {
|
|
|
+ switch (common_status_data_.control_source) {
|
|
|
case SDK_CONTROL_MODE::nav_control: {
|
|
|
curr_mode = CONTROL_MODE::NAVI_CONTROL;
|
|
|
break;
|
|
@@ -591,7 +581,7 @@ void SaturnController::publishGait() {
|
|
|
curr_scene = Robot_Gait::TROT;
|
|
|
break;
|
|
|
}
|
|
|
- case SDK_SCENE_TYPE::STONE: {
|
|
|
+ case SDK_SCENE_TYPE::ROUGH: {
|
|
|
curr_scene = Robot_Gait::SLOPE;
|
|
|
break;
|
|
|
}
|
|
@@ -643,14 +633,14 @@ void SaturnController::publishRobotMode() {
|
|
|
auto robot_mode_state = std_msgs::msg::Int32();
|
|
|
|
|
|
if ((is_robot_in_idle_state_ == true) &&
|
|
|
- (common_status_data_.joy_mode ==
|
|
|
+ (common_status_data_.control_source ==
|
|
|
robot_control::common::CONTROL_SOURCE_MODE::nav_control)) {
|
|
|
robot_mode_state.data = 0;
|
|
|
- } else if (common_status_data_.joy_mode ==
|
|
|
+ } else if (common_status_data_.control_source ==
|
|
|
robot_control::common::CONTROL_SOURCE_MODE::joy_control) {
|
|
|
robot_mode_state.data = 1;
|
|
|
} else if ((is_robot_in_idle_state_ == false) &&
|
|
|
- (common_status_data_.joy_mode ==
|
|
|
+ (common_status_data_.control_source ==
|
|
|
robot_control::common::CONTROL_SOURCE_MODE::nav_control)) {
|
|
|
robot_mode_state.data = 2;
|
|
|
} else if (common_status_data_.cur_scene ==
|