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

Report positive value for h480 yawMax and negative value for yawMin #1061

Merged
merged 1 commit into from
Jan 29, 2025
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
4 changes: 2 additions & 2 deletions src/gazebo_gimbal_controller_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -659,8 +659,8 @@ void GimbalControllerPlugin::SendGimbalDeviceInformation()
const float rollMin = this->rollJoint->LowerLimit(0);
const float pitchMax = this->pitchJoint->UpperLimit(0);
const float pitchMin = this->pitchJoint->LowerLimit(0);
const float yawMax = this->yawJoint->LowerLimit(0);
const float yawMin = this->yawJoint->UpperLimit(0);
const float yawMax = this->yawJoint->UpperLimit(0);
const float yawMin = this->yawJoint->LowerLimit(0);

mavlink_message_t msg;
mavlink_msg_gimbal_device_information_pack_chan(
Expand Down
Loading