diff --git a/src/rl_sar/CMakeLists.txt b/src/rl_sar/CMakeLists.txt index 9a0c127..72cb6be 100644 --- a/src/rl_sar/CMakeLists.txt +++ b/src/rl_sar/CMakeLists.txt @@ -29,7 +29,8 @@ find_package(rclpy REQUIRED) find_package(gazebo_msgs REQUIRED) find_package(std_srvs REQUIRED) -find_package(Python3 COMPONENTS Interpreter Development REQUIRED) +# Make sure to find Python 3.8 +find_package(Python3 3.8 EXACT COMPONENTS Interpreter Development REQUIRED) link_directories(/usr/local/lib) include_directories(${YAML_CPP_INCLUDE_DIR}) diff --git a/src/rl_sar/scripts/rl_sim.py b/src/rl_sar/scripts/rl_sim.py index 5e0d482..7a85841 100755 --- a/src/rl_sar/scripts/rl_sim.py +++ b/src/rl_sar/scripts/rl_sim.py @@ -54,7 +54,7 @@ class RL_Sim(RL, Node): self.ReadYaml(self.robot_name) for i in range(len(self.params.observations)): if self.params.observations[i] == "ang_vel": - self.params.observations[i] = "ang_vel_world" + self.params.observations[i] = "ang_vel_body" # init rl torch.set_grad_enabled(False) diff --git a/src/rl_sar/src/rl_sim.cpp b/src/rl_sar/src/rl_sim.cpp index d60ea93..4030741 100644 --- a/src/rl_sar/src/rl_sim.cpp +++ b/src/rl_sar/src/rl_sim.cpp @@ -49,10 +49,9 @@ RL_Sim::RL_Sim() this->ReadYaml(this->robot_name); for (std::string &observation : this->params.observations) { - // In Gazebo, the coordinate system for angular velocity is in the world coordinate system. if (observation == "ang_vel") { - observation = "ang_vel_world"; + observation = "ang_vel_body"; } }