Skip to content

Commit

Permalink
Report positive value for h480 yawMax and negative value for yawMin
Browse files Browse the repository at this point in the history
The h480 sim gimbal has no limit on its yaw axis. Before, it was reporting its yawMax as -1e+16 (value came from typhoon_h480.sdf.jinja:247) and its yawMin as 1e+16 (value came from typhoon_h480.sdf.jinja:248). The sign of these 2 needed to be switched, which is the fix made by this commit.

The MAVLink GIMBAL_DEVICE_INFORMATION message does not specify how to represent infinity, but it does specify "positive: to the right, negative: to the left". Gazebo already considers the right the positive direction, and handles commands as expected. This commit just fixes the yawMin/yawMax limit reporting.
  • Loading branch information
gillamkid committed Jan 25, 2025
1 parent c0e0751 commit 4187c6c
Showing 1 changed file with 2 additions and 2 deletions.
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

0 comments on commit 4187c6c

Please sign in to comment.