Skip to content

Commit

Permalink
dummy
Browse files Browse the repository at this point in the history
  • Loading branch information
haitomatic committed Jan 9, 2024
1 parent cd906ab commit 9bf8bcb
Showing 1 changed file with 2 additions and 21 deletions.
23 changes: 2 additions & 21 deletions src/gazebo_mavlink_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -273,8 +273,8 @@ void GazeboMavlinkInterface::PoseCallback(const gz::msgs::Pose_V &_msg){
hil_state_quat.attitude_quaternion[2] = q_nb.Y();
hil_state_quat.attitude_quaternion[3] = q_nb.Z();

hil_state_quat.lat = pose_position.y() * 1e3;
hil_state_quat.lon = pose_position.x() * 1e3;
hil_state_quat.lat = pose_position.x() * 1e3;
hil_state_quat.lon = pose_position.y() * 1e3;
hil_state_quat.alt = pose_position.z() * 1e3;

mavlink_message_t msg;
Expand Down Expand Up @@ -380,25 +380,6 @@ void GazeboMavlinkInterface::SendSensorMessages(const gz::sim::UpdateInfo &_info
const gz::msgs::IMU last_imu_message = last_imu_message_;
last_imu_message_mutex_.unlock();

gz::math::Quaterniond q_gr = gz::math::Quaterniond(
last_imu_message.orientation().w(),
last_imu_message.orientation().x(),
last_imu_message.orientation().y(),
last_imu_message.orientation().z());

/*
bool should_send_imu = false;
if (!enable_lockstep_) {
std::chrono::steady_clock::duration current_time = _info.simTime;
double dt = (current_time - last_imu_time_).count();
if (imu_update_interval_!=0 && dt >= imu_update_interval_) {
should_send_imu = true;
last_imu_time_ = current_time;
}
}
*/

// send always accel and gyro data (not dependent of the bitmask)
// required so to keep the timestamps on sync and the lockstep can
Expand Down

0 comments on commit 9bf8bcb

Please sign in to comment.