Browse Source

[1 feat] 新增斜坡步态

liuhj31 5 months ago
parent
commit
71ac3818d7
1 changed files with 9 additions and 3 deletions
  1. 9 3
      saturn_controller/src/saturn_controller.cpp

+ 9 - 3
saturn_controller/src/saturn_controller.cpp

@@ -156,7 +156,8 @@ namespace saturn_ros2
         {
             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::STAIRS) ||
+                (common_status_data_.cur_scene == robot_control::common::SCENE_TYPE::STONE))
             {
                 result = rcClientInterfaceSetScene(robot_control::common::NAV_OR_JOY_MODE::nav_control,
                                                    common::SCENE_TYPE::LIE_DOWN);
@@ -205,8 +206,9 @@ namespace saturn_ros2
         }
         else if ("SlopeGait" == request->comamnd_name)
         {
-            SPDLOG_WARN("SlopeGait is not supported yet.");
-            result = false;
+            SPDLOG_INFO("SlopeGait is called");
+            result = rcClientInterfaceSetScene(robot_control::common::NAV_OR_JOY_MODE::nav_control,
+                                               common::SCENE_TYPE::STONE);
         }
         else if ("VstairsGait" == request->comamnd_name)
         {
@@ -494,6 +496,10 @@ namespace saturn_ros2
         {
             gait_scene_state.data = 4;
         }
+        else if (common_status_data_.cur_scene == robot_control::common::SCENE_TYPE::STONE)
+        {
+            gait_scene_state.data = 5;
+        }
         else
         {
             gait_scene_state.data = 0;