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

mission: hack to set gimbal angle absolute for now #552

Merged
merged 2 commits into from
Sep 20, 2018
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
56 changes: 55 additions & 1 deletion plugins/mission/mission_impl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -436,6 +436,7 @@ void MissionImpl::assemble_mavlink_messages()
float last_z;

unsigned item_i = 0;

for (auto item : _mission_data.mission_items) {
MissionItemImpl &mission_item_impl = (*(item)->_impl);

Expand Down Expand Up @@ -509,6 +510,44 @@ void MissionImpl::assemble_mavlink_messages()

if (std::isfinite(mission_item_impl.get_gimbal_yaw_deg()) ||
std::isfinite(mission_item_impl.get_gimbal_pitch_deg())) {
if (_enable_absolute_gimbal_yaw_angle) {
// We need to configure the gimbal to use an absolute angle.

// Current is the 0th waypoint
uint8_t current =
((_mission_data.mavlink_mission_item_messages.size() == 0) ? 1 : 0);

uint8_t autocontinue = 1;

auto message_gimbal_configure = std::make_shared<mavlink_message_t>();
mavlink_msg_mission_item_int_pack(
GCSClient::system_id,
GCSClient::component_id,
message_gimbal_configure.get(),
_parent->get_system_id(),
_parent->get_autopilot_id(),
_mission_data.mavlink_mission_item_messages.size(),
MAV_FRAME_MISSION,
MAV_CMD_DO_MOUNT_CONFIGURE,
current,
autocontinue,
MAV_MOUNT_MODE_MAVLINK_TARGETING,
0.0f, // stabilize roll
0.0f, // stabilize pitch
1.0f, // stabilize yaw, FIXME: for now we use this for an absolute yaw angle,
// because it works.
0,
0,
2.0f, // eventually this is the correct flag to set absolute yaw angle.
MAV_MISSION_TYPE_MISSION);

_mission_data.mavlink_mission_item_to_mission_item_indices.insert(
std::pair<int, int>{
static_cast<int>(_mission_data.mavlink_mission_item_messages.size()),
item_i});
_mission_data.mavlink_mission_item_messages.push_back(message_gimbal_configure);
}

// The gimbal has changed, we need to add a gimbal command.

// Current is the 0th waypoint
Expand Down Expand Up @@ -737,13 +776,28 @@ void MissionImpl::assemble_mission_items()

} else if (it->command == MAV_CMD_DO_MOUNT_CONTROL) {
if (int(it->z) != MAV_MOUNT_MODE_MAVLINK_TARGETING) {
LogErr() << "Gimbal mount mode unsupported";
LogErr() << "Gimbal mount control mode unsupported";
result = Mission::Result::UNSUPPORTED;
break;
}

new_mission_item->set_gimbal_pitch_and_yaw(it->param1, it->param3);

} else if (it->command == MAV_CMD_DO_MOUNT_CONFIGURE) {
if (int(it->param1) != MAV_MOUNT_MODE_MAVLINK_TARGETING) {
LogErr() << "Gimbal mount configure mode unsupported";
result = Mission::Result::UNSUPPORTED;
break;
}

// FIXME: ultimately param4 doesn't count anymore and
// param7 holds the truth.
if (int(it->param4) == 1 || int(it->z) == 2) {
_enable_absolute_gimbal_yaw_angle = true;
} else {
_enable_absolute_gimbal_yaw_angle = false;
}

} else if (it->command == MAV_CMD_IMAGE_START_CAPTURE) {
if (it->param2 > 0 && int(it->param3) == 0) {
new_mission_item->set_camera_action(
Expand Down
4 changes: 4 additions & 0 deletions plugins/mission/mission_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -122,6 +122,10 @@ class MissionImpl : public PluginImplBase {

bool _enable_return_to_launch_after_mission{false};

// FIXME: This is hardcoded for now because it is urgently needed for 3DR with Yuneec H520.
// Ultimate it needs a setter.
bool _enable_absolute_gimbal_yaw_angle{true};

static constexpr unsigned MAX_RETRIES = 3;

static constexpr uint8_t VEHICLE_MODE_FLAG_CUSTOM_MODE_ENABLED = 1;
Expand Down