Skip to content

Commit

Permalink
Fix incorrect force-torque sensor vec population (#296)
Browse files Browse the repository at this point in the history
(cherry picked from commit fdcd7aa)
  • Loading branch information
mateusmenezes95 authored and mergify[bot] committed Apr 8, 2024
1 parent 6621895 commit b6a06ea
Showing 1 changed file with 6 additions and 6 deletions.
12 changes: 6 additions & 6 deletions gazebo_ros2_control/src/gazebo_system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -561,13 +561,13 @@ hardware_interface::return_type GazeboSystem::read(

for (unsigned int j = 0; j < this->dataPtr->sim_ft_sensors_.size(); j++) {
auto sim_ft_sensor = this->dataPtr->sim_ft_sensors_[j];
this->dataPtr->imu_sensor_data_[j][0] = sim_ft_sensor->Force().X();
this->dataPtr->imu_sensor_data_[j][1] = sim_ft_sensor->Force().Y();
this->dataPtr->imu_sensor_data_[j][2] = sim_ft_sensor->Force().Z();
this->dataPtr->ft_sensor_data_[j][0] = sim_ft_sensor->Force().X();
this->dataPtr->ft_sensor_data_[j][1] = sim_ft_sensor->Force().Y();
this->dataPtr->ft_sensor_data_[j][2] = sim_ft_sensor->Force().Z();

this->dataPtr->imu_sensor_data_[j][3] = sim_ft_sensor->Torque().X();
this->dataPtr->imu_sensor_data_[j][4] = sim_ft_sensor->Torque().Y();
this->dataPtr->imu_sensor_data_[j][5] = sim_ft_sensor->Torque().Z();
this->dataPtr->ft_sensor_data_[j][3] = sim_ft_sensor->Torque().X();
this->dataPtr->ft_sensor_data_[j][4] = sim_ft_sensor->Torque().Y();
this->dataPtr->ft_sensor_data_[j][5] = sim_ft_sensor->Torque().Z();
}
return hardware_interface::return_type::OK;
}
Expand Down

0 comments on commit b6a06ea

Please sign in to comment.