diff --git a/include/gazebo_mavlink_interface.h b/include/gazebo_mavlink_interface.h index ee94224..c5cdb0c 100644 --- a/include/gazebo_mavlink_interface.h +++ b/include/gazebo_mavlink_interface.h @@ -208,7 +208,7 @@ namespace mavlink_interface bool enable_lockstep_ = false; double speed_factor_ = 1.0; uint8_t previous_imu_seq_ = 0; - uint8_t update_skip_factor_ = 1; + uint8_t update_skip_factor_ = 3; std::string mavlink_hostname_str_; struct hostent *hostptr_{nullptr}; diff --git a/src/gazebo_mavlink_interface.cpp b/src/gazebo_mavlink_interface.cpp index cebab32..75aa8d5 100644 --- a/src/gazebo_mavlink_interface.cpp +++ b/src/gazebo_mavlink_interface.cpp @@ -237,7 +237,7 @@ void GazeboMavlinkInterface::PreUpdate(const gz::sim::UpdateInfo &_info, mavlink_interface_->ReadMAVLinkMessages(); // Always send Gyro and Accel data at full rate (= sim update rate) - //SendSensorMessages(_info); + SendSensorMessages(_info); handle_actuator_controls(_info); @@ -298,7 +298,6 @@ void GazeboMavlinkInterface::PoseCallback(const gz::msgs::Pose_V &_msg){ void GazeboMavlinkInterface::ImuCallback(const gz::msgs::IMU &_msg) { const std::lock_guard lock(last_imu_message_mutex_); last_imu_message_ = _msg; - std::cout << "ImuCallback with data " << last_imu_message_.linear_acceleration().z() << std::endl; } void GazeboMavlinkInterface::BarometerCallback(const gz::msgs::FluidPressure &_msg) {