Skip to content

Commit

Permalink
Update imu_sensor.hpp (ros-controls#893)
Browse files Browse the repository at this point in the history
Covariances values should come from the IMU_Broadcaster, like the frame_id or the time
  • Loading branch information
flochre authored Jan 11, 2023
1 parent c147782 commit 6aae3e1
Showing 1 changed file with 0 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -114,17 +114,14 @@ class IMUSensor : public SemanticComponentInterface<sensor_msgs::msg::Imu>
message.orientation.y = orientation_[1];
message.orientation.z = orientation_[2];
message.orientation.w = orientation_[3];
message.orientation_covariance.fill(.0);

message.angular_velocity.x = angular_velocity_[0];
message.angular_velocity.y = angular_velocity_[1];
message.angular_velocity.z = angular_velocity_[2];
message.angular_velocity_covariance.fill(.0);

message.linear_acceleration.x = linear_acceleration_[0];
message.linear_acceleration.y = linear_acceleration_[1];
message.linear_acceleration.z = linear_acceleration_[2];
message.linear_acceleration_covariance.fill(.0);

return true;
}
Expand Down

0 comments on commit 6aae3e1

Please sign in to comment.