Skip to content

Commit b41a05b

Browse files
Generate from proto
1 parent 9b1778c commit b41a05b

File tree

8 files changed

+302
-62
lines changed

8 files changed

+302
-62
lines changed

proto

src/mavsdk/plugins/mission_raw/include/plugins/mission_raw/mission_raw.h

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -124,7 +124,9 @@ class MissionRaw : public PluginBase {
124124
std::vector<MissionItem> mission_items{}; /**< @brief Mission items */
125125
std::vector<MissionItem> geofence_items{}; /**< @brief Geofence items */
126126
std::vector<MissionItem> rally_items{}; /**< @brief Rally items */
127-
std::optional<MissionItem> plannedHomePosition;
127+
bool has_planned_home_position{}; /**< @brief Whether it contains a planned home position
128+
element or not */
129+
MissionItem planned_home_position{}; /**< @brief Planned home position */
128130
};
129131

130132
/**

src/mavsdk/plugins/mission_raw/mission_import.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,7 @@ MissionImport::parse_json(const std::string& raw_json, Sender::Autopilot autopil
3030

3131
MissionRaw::MissionImportData import_data;
3232
import_data.mission_items = maybe_mission_items.first.value();
33-
import_data.plannedHomePosition = maybe_mission_items.second.value();
33+
import_data.planned_home_position = maybe_mission_items.second.value();
3434

3535
return {MissionRaw::Result::Success, import_data};
3636
}
@@ -48,7 +48,9 @@ bool MissionImport::check_overall_version(const Json::Value& root)
4848
return true;
4949
}
5050

51-
std::pair<std::optional<std::vector<MissionRaw::MissionItem>>, std::optional<MissionRaw::MissionItem>>
51+
std::pair<
52+
std::optional<std::vector<MissionRaw::MissionItem>>,
53+
std::optional<MissionRaw::MissionItem>>
5254
MissionImport::import_mission(const Json::Value& root, Sender::Autopilot autopilot)
5355
{
5456
// We need a mission part.
@@ -134,9 +136,7 @@ MissionImport::import_mission(const Json::Value& root, Sender::Autopilot autopil
134136

135137
// Add home position at 0 for ArduPilot
136138
if (autopilot == Sender::Autopilot::ArduPilot && home_item.has_value()) {
137-
mission_items.insert(
138-
mission_items.begin(),
139-
home_item.value());
139+
mission_items.insert(mission_items.begin(), home_item.value());
140140
}
141141

142142
// Returning an empty vector is ok here if there were really no mission items.

src/mavsdk/plugins/mission_raw/mission_import.h

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,9 @@ class MissionImport {
1616

1717
private:
1818
static bool check_overall_version(const Json::Value& root);
19-
static std::pair<std::optional<std::vector<MissionRaw::MissionItem>>, std::optional<MissionRaw::MissionItem>>
19+
static std::pair<
20+
std::optional<std::vector<MissionRaw::MissionItem>>,
21+
std::optional<MissionRaw::MissionItem>>
2022
import_mission(const Json::Value& root, SystemImpl::Autopilot autopilot);
2123
static std::optional<MissionRaw::MissionItem>
2224
import_simple_mission_item(const Json::Value& json_item);

src/mavsdk/plugins/mission_raw/mission_raw.cpp

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -170,7 +170,9 @@ std::ostream& operator<<(std::ostream& str, MissionRaw::MissionItem const& missi
170170
bool operator==(const MissionRaw::MissionImportData& lhs, const MissionRaw::MissionImportData& rhs)
171171
{
172172
return (rhs.mission_items == lhs.mission_items) && (rhs.geofence_items == lhs.geofence_items) &&
173-
(rhs.rally_items == lhs.rally_items);
173+
(rhs.rally_items == lhs.rally_items) &&
174+
(rhs.has_planned_home_position == lhs.has_planned_home_position) &&
175+
(rhs.planned_home_position == lhs.planned_home_position);
174176
}
175177

176178
std::ostream&
@@ -199,6 +201,9 @@ operator<<(std::ostream& str, MissionRaw::MissionImportData const& mission_impor
199201
str << *it;
200202
str << (it + 1 != mission_import_data.rally_items.end() ? ", " : "]\n");
201203
}
204+
str << " has_planned_home_position: " << mission_import_data.has_planned_home_position
205+
<< '\n';
206+
str << " planned_home_position: " << mission_import_data.planned_home_position << '\n';
202207
str << '}';
203208
return str;
204209
}

src/mavsdk_server/src/generated/mission_raw/mission_raw.pb.cc

Lines changed: 133 additions & 53 deletions
Some generated files are not rendered by default. Learn more about customizing how changed files appear on GitHub.

src/mavsdk_server/src/generated/mission_raw/mission_raw.pb.h

Lines changed: 141 additions & 0 deletions
Some generated files are not rendered by default. Learn more about customizing how changed files appear on GitHub.

src/mavsdk_server/src/plugins/mission_raw/mission_raw_service_impl.h

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -150,6 +150,11 @@ class MissionRawServiceImpl final : public rpc::mission_raw::MissionRawService::
150150
ptr->CopyFrom(*translateToRpcMissionItem(elem).release());
151151
}
152152

153+
rpc_obj->set_has_planned_home_position(mission_import_data.has_planned_home_position);
154+
155+
rpc_obj->set_allocated_planned_home_position(
156+
translateToRpcMissionItem(mission_import_data.planned_home_position).release());
157+
153158
return rpc_obj;
154159
}
155160

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

181+
obj.has_planned_home_position = mission_import_data.has_planned_home_position();
182+
183+
obj.planned_home_position =
184+
translateFromRpcMissionItem(mission_import_data.planned_home_position());
185+
176186
return obj;
177187
}
178188

0 commit comments

Comments
 (0)