diff --git a/src/gazebo_mavlink_interface.cpp b/src/gazebo_mavlink_interface.cpp index 6481017..cebab32 100644 --- a/src/gazebo_mavlink_interface.cpp +++ b/src/gazebo_mavlink_interface.cpp @@ -298,7 +298,7 @@ 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_.orientation().z() << std::endl; + std::cout << "ImuCallback with data " << last_imu_message_.linear_acceleration().z() << std::endl; } void GazeboMavlinkInterface::BarometerCallback(const gz::msgs::FluidPressure &_msg) { @@ -473,6 +473,7 @@ void GazeboMavlinkInterface::PublishRotorVelocities( gz::sim::EntityComponentManager &_ecm, const Eigen::VectorXd &_vels) { + std::cout << "number of motors " << _vels.size() << std::endl; if (_vels.size() != rotor_velocity_message_.velocity_size()) { rotor_velocity_message_.mutable_velocity()->Resize(_vels.size(), 0); diff --git a/src/mavlink_interface.cpp b/src/mavlink_interface.cpp index d8c92b6..bff423f 100644 --- a/src/mavlink_interface.cpp +++ b/src/mavlink_interface.cpp @@ -483,7 +483,6 @@ void MavlinkInterface::handle_actuator_controls(mavlink_message_t *msg) for (int i = 0; i < input_reference_.size(); i++) { input_reference_[i] = controls.controls[i]; } - std::cout << "input_reference_ : " << input_reference_[0] << std::endl; received_actuator_ = true; received_first_actuator_ = true; }