Skip to content

Commit

Permalink
Generate from proto
Browse files Browse the repository at this point in the history
  • Loading branch information
JonasVautherin committed Aug 15, 2023
1 parent 9b1778c commit b41a05b
Show file tree
Hide file tree
Showing 8 changed files with 302 additions and 62 deletions.
2 changes: 1 addition & 1 deletion proto
Original file line number Diff line number Diff line change
Expand Up @@ -124,7 +124,9 @@ class MissionRaw : public PluginBase {
std::vector<MissionItem> mission_items{}; /**< @brief Mission items */
std::vector<MissionItem> geofence_items{}; /**< @brief Geofence items */
std::vector<MissionItem> rally_items{}; /**< @brief Rally items */
std::optional<MissionItem> plannedHomePosition;
bool has_planned_home_position{}; /**< @brief Whether it contains a planned home position
element or not */
MissionItem planned_home_position{}; /**< @brief Planned home position */
};

/**
Expand Down
10 changes: 5 additions & 5 deletions src/mavsdk/plugins/mission_raw/mission_import.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ MissionImport::parse_json(const std::string& raw_json, Sender::Autopilot autopil

MissionRaw::MissionImportData import_data;
import_data.mission_items = maybe_mission_items.first.value();
import_data.plannedHomePosition = maybe_mission_items.second.value();
import_data.planned_home_position = maybe_mission_items.second.value();

return {MissionRaw::Result::Success, import_data};
}
Expand All @@ -48,7 +48,9 @@ bool MissionImport::check_overall_version(const Json::Value& root)
return true;
}

std::pair<std::optional<std::vector<MissionRaw::MissionItem>>, std::optional<MissionRaw::MissionItem>>
std::pair<
std::optional<std::vector<MissionRaw::MissionItem>>,
std::optional<MissionRaw::MissionItem>>
MissionImport::import_mission(const Json::Value& root, Sender::Autopilot autopilot)
{
// We need a mission part.
Expand Down Expand Up @@ -134,9 +136,7 @@ MissionImport::import_mission(const Json::Value& root, Sender::Autopilot autopil

// Add home position at 0 for ArduPilot
if (autopilot == Sender::Autopilot::ArduPilot && home_item.has_value()) {
mission_items.insert(
mission_items.begin(),
home_item.value());
mission_items.insert(mission_items.begin(), home_item.value());
}

// Returning an empty vector is ok here if there were really no mission items.
Expand Down
4 changes: 3 additions & 1 deletion src/mavsdk/plugins/mission_raw/mission_import.h
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,9 @@ class MissionImport {

private:
static bool check_overall_version(const Json::Value& root);
static std::pair<std::optional<std::vector<MissionRaw::MissionItem>>, std::optional<MissionRaw::MissionItem>>
static std::pair<
std::optional<std::vector<MissionRaw::MissionItem>>,
std::optional<MissionRaw::MissionItem>>
import_mission(const Json::Value& root, SystemImpl::Autopilot autopilot);
static std::optional<MissionRaw::MissionItem>
import_simple_mission_item(const Json::Value& json_item);
Expand Down
7 changes: 6 additions & 1 deletion src/mavsdk/plugins/mission_raw/mission_raw.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -170,7 +170,9 @@ std::ostream& operator<<(std::ostream& str, MissionRaw::MissionItem const& missi
bool operator==(const MissionRaw::MissionImportData& lhs, const MissionRaw::MissionImportData& rhs)
{
return (rhs.mission_items == lhs.mission_items) && (rhs.geofence_items == lhs.geofence_items) &&
(rhs.rally_items == lhs.rally_items);
(rhs.rally_items == lhs.rally_items) &&
(rhs.has_planned_home_position == lhs.has_planned_home_position) &&
(rhs.planned_home_position == lhs.planned_home_position);
}

std::ostream&
Expand Down Expand Up @@ -199,6 +201,9 @@ operator<<(std::ostream& str, MissionRaw::MissionImportData const& mission_impor
str << *it;
str << (it + 1 != mission_import_data.rally_items.end() ? ", " : "]\n");
}
str << " has_planned_home_position: " << mission_import_data.has_planned_home_position
<< '\n';
str << " planned_home_position: " << mission_import_data.planned_home_position << '\n';
str << '}';
return str;
}
Expand Down
186 changes: 133 additions & 53 deletions src/mavsdk_server/src/generated/mission_raw/mission_raw.pb.cc

Large diffs are not rendered by default.

141 changes: 141 additions & 0 deletions src/mavsdk_server/src/generated/mission_raw/mission_raw.pb.h

Some generated files are not rendered by default. Learn more about how customized files appear on GitHub.

Original file line number Diff line number Diff line change
Expand Up @@ -150,6 +150,11 @@ class MissionRawServiceImpl final : public rpc::mission_raw::MissionRawService::
ptr->CopyFrom(*translateToRpcMissionItem(elem).release());
}

rpc_obj->set_has_planned_home_position(mission_import_data.has_planned_home_position);

rpc_obj->set_allocated_planned_home_position(
translateToRpcMissionItem(mission_import_data.planned_home_position).release());

return rpc_obj;
}

Expand All @@ -173,6 +178,11 @@ class MissionRawServiceImpl final : public rpc::mission_raw::MissionRawService::
static_cast<mavsdk::rpc::mission_raw::MissionItem>(elem)));
}

obj.has_planned_home_position = mission_import_data.has_planned_home_position();

obj.planned_home_position =
translateFromRpcMissionItem(mission_import_data.planned_home_position());

return obj;
}

Expand Down

0 comments on commit b41a05b

Please sign in to comment.