Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Measure IMU orientation with respect to world (ros2) #1064

Merged
merged 3 commits into from
Jun 2, 2020
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
20 changes: 20 additions & 0 deletions gazebo_plugins/src/gazebo_ros_imu_sensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -69,6 +69,26 @@ void GazeboRosImuSensor::Load(gazebo::sensors::SensorPtr _sensor, sdf::ElementPt
return;
}

bool initial_orientation_as_reference = false;
if (!_sdf->HasElement("initial_orientation_as_reference")) {
RCLCPP_INFO_STREAM(
impl_->ros_node_->get_logger(),
"<initial_orientation_as_reference> is unset, using default value of false "
"to comply with REP 145 (world as orientation reference)");
} else {
initial_orientation_as_reference = _sdf->Get<bool>("initial_orientation_as_reference");
}

if (initial_orientation_as_reference) {
RCLCPP_WARN_STREAM(
impl_->ros_node_->get_logger(),
"<initial_orientation_as_reference> set to true, this behavior is deprecated "
"as it does not comply with REP 145.");
} else {
// This complies with REP 145
impl_->sensor_->SetWorldToReferenceOrientation(ignition::math::Quaterniond::Identity);
}

impl_->pub_ = impl_->ros_node_->create_publisher<sensor_msgs::msg::Imu>(
"~/out", qos.get_publisher_qos("~/out", rclcpp::SensorDataQoS()));

Expand Down