fix: the angular velocity of the IMU topic is in the body coordinate system. Close #39

This commit is contained in:
fan-ziqi 2024-11-13 10:56:13 +08:00
parent 6fd0136d44
commit 4124f78e1c
2 changed files with 2 additions and 3 deletions

View File

@ -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)

View File

@ -41,10 +41,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";
}
}