Skip to content

Commit

Permalink
update
Browse files Browse the repository at this point in the history
  • Loading branch information
haitomatic committed Nov 8, 2023
1 parent bab4430 commit b08fb57
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 3 deletions.
2 changes: 1 addition & 1 deletion include/gazebo_mavlink_interface.h
Original file line number Diff line number Diff line change
Expand Up @@ -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};
Expand Down
3 changes: 1 addition & 2 deletions src/gazebo_mavlink_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);

Expand Down Expand Up @@ -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<std::mutex> 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) {
Expand Down

0 comments on commit b08fb57

Please sign in to comment.