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

MissionManager: Support for MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW #10833

Merged
Show file tree
Hide file tree
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
45 changes: 45 additions & 0 deletions src/MissionManager/MavCmdInfoCommon.json
Original file line number Diff line number Diff line change
Expand Up @@ -910,6 +910,51 @@
"enumValues": "0,1,2,3,4"
}
},
{
"id": 1000,
"rawName": "MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW",
"friendlyName": "Gimbal Manager PitchYaw" ,
"description": "Control the gimbal during the mission",
"category": "Advanced",
"param1": {
"label": "Pitch",
"default": 0,
"units": "deg",
"decimalPlaces": 2
},
"param2": {
"label": "Yaw",
"default": 0,
"units": "deg",
"decimalPlaces": 2
},
"param3": {
"label": "Pitch rate",
"default": 0,
"units": "deg/s",
"decimalPlaces": 2
},
"param4": {
"label": "Yaw rate",
"default": 0,
"units": "deg/s",
"decimalPlaces": 2
},
"param5": {
"label": "Follow yaw",
"default": 0,
"decimalPlaces": 0,
"enumStrings": "Follow yaw, Lock yaw",
"enumValues": "0,16"
},
"param7": {
"label": "Gimbal",
"default": 0,
"decimalPlaces": 0,
"enumStrings": "Primary,first gimbal,second gimbal",
"enumValues": "0,1,2"
}
},
{
"id": 206,
"rawName": "MAV_CMD_DO_SET_CAM_TRIGG_DIST",
Expand Down
1 change: 1 addition & 0 deletions src/MissionManager/MissionController.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1576,6 +1576,7 @@ void MissionController::_recalcMissionFlightStatus()
case MAV_CMD_NAV_ROI:
case MAV_CMD_DO_SET_ROI_LOCATION:
case MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET:
case MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW:
_missionFlightStatus.gimbalYaw = qQNaN();
_missionFlightStatus.gimbalPitch = qQNaN();
break;
Expand Down