Skip to content

Commit

Permalink
the names inspection task and inspection plan are not used to avoid c…
Browse files Browse the repository at this point in the history
…onfusion

each waypoint is associated with the inspection task identifier
update mavlink version
  • Loading branch information
fcuesta committed Jun 2, 2021
1 parent 67f4781 commit 96d74fd
Show file tree
Hide file tree
Showing 44 changed files with 2,865 additions and 2,869 deletions.
32 changes: 17 additions & 15 deletions examples/piloting_inspection/piloting_gcs_inspection_example.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,8 @@ using namespace std::chrono;
#define RESULT_CONSOLE_TEXT "\033[34m" // Turn text on console blue
#define NORMAL_CONSOLE_TEXT "\033[0m" // Restore normal console colour

static InspectionBase::InspectionItem make_inspection_item(
static InspectionBase::WaypointItem make_waypoint_item(
uint32_t task_id,
uint16_t command,
uint8_t autocontinue,
float param1,
Expand Down Expand Up @@ -67,24 +68,23 @@ int main(int, char**)

{
std::cout << "Creating inspection to be sent..." << std::endl;
std::vector<InspectionBase::InspectionItem> inspection_items;
inspection_items.push_back(make_inspection_item(
MAV_CMD_NAV_WAYPOINT, 1, 1.1f, 2.2f, 3.3f, 4.4f, 5.5f, 6.6f, 7.7f));
inspection_items.push_back(make_inspection_item(
MAV_CMD_NAV_WAYPOINT, 1, 2.2f, 3.3f, 4.4f, 5.5f, 6.6f, 7.7f, 8.8f));
inspection_items.push_back(make_inspection_item(
MAV_CMD_NAV_WAYPOINT, 1, 3.3f, 4.4f, 5.5f, 6.6f, 7.7f, 8.8f, 9.9f));
InspectionBase::InspectionPlan inspection_plan{};
inspection_plan.mission_id = 25;
inspection_plan.inspection_items = inspection_items;
std::cout << RESULT_CONSOLE_TEXT << inspection_plan << NORMAL_CONSOLE_TEXT << std::endl;
std::vector<InspectionBase::WaypointItem> waypoint_items;
waypoint_items.push_back(make_waypoint_item(
12345, MAV_CMD_NAV_WAYPOINT, 1, 1.1f, 2.2f, 3.3f, 4.4f, 5.5f, 6.6f, 7.7f));
waypoint_items.push_back(make_waypoint_item(
12346, MAV_CMD_NAV_WAYPOINT, 1, 2.2f, 3.3f, 4.4f, 5.5f, 6.6f, 7.7f, 8.8f));
waypoint_items.push_back(make_waypoint_item(
12347, MAV_CMD_NAV_WAYPOINT, 1, 3.3f, 4.4f, 5.5f, 6.6f, 7.7f, 8.8f, 9.9f));
InspectionBase::WaypointList waypoint_list{};
waypoint_list.items = waypoint_items;
std::cout << RESULT_CONSOLE_TEXT << waypoint_list << NORMAL_CONSOLE_TEXT << std::endl;

std::cout << "Uploading inspection..." << std::endl;
auto prom = std::make_shared<
std::promise<std::pair<InspectionBase::Result, InspectionBase::Ack>>>();
auto future_result = prom->get_future();
inspection.upload_inspection_async(
inspection_plan, [prom](InspectionBase::Result result, InspectionBase::Ack ack) {
waypoint_list, [prom](InspectionBase::Result result, InspectionBase::Ack ack) {
prom->set_value(std::make_pair<>(result, ack));
});

Expand Down Expand Up @@ -130,7 +130,8 @@ int main(int, char**)
return EXIT_SUCCESS;
}

InspectionBase::InspectionItem make_inspection_item(
InspectionBase::WaypointItem make_waypoint_item(
uint32_t task_id,
uint16_t command,
uint8_t autocontinue,
float param1,
Expand All @@ -141,7 +142,8 @@ InspectionBase::InspectionItem make_inspection_item(
float y,
float z)
{
InspectionBase::InspectionItem new_item{};
InspectionBase::WaypointItem new_item{};
new_item.task_id = task_id;
new_item.command = command;
new_item.autocontinue = autocontinue;
new_item.param1 = param1;
Expand Down
46 changes: 23 additions & 23 deletions examples/piloting_inspection/piloting_robot_inspection_example.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,18 +58,18 @@ int main(int, char**)

auto inspection_rv = InspectionRoboticVehicle{target_system};

std::mutex local_inspection_mutex;
InspectionBase::InspectionPlan local_inspection_plan;
std::mutex local_waypoint_list_mutex;
InspectionBase::WaypointList local_waypoint_list;

inspection_rv.download_inspection_async(
[&](InspectionBase::Result result, InspectionBase::InspectionPlan inspection_plan) {
[&](InspectionBase::Result result, InspectionBase::WaypointList waypoint_list) {
std::cout << RESULT_CONSOLE_TEXT << "Inspection download result is: " << result
<< NORMAL_CONSOLE_TEXT << std::endl;
std::cout << RESULT_CONSOLE_TEXT << inspection_plan << NORMAL_CONSOLE_TEXT << std::endl;
std::cout << RESULT_CONSOLE_TEXT << waypoint_list << NORMAL_CONSOLE_TEXT << std::endl;

if (result == InspectionBase::Result::Success) {
std::lock_guard<std::mutex> lock(local_inspection_mutex);
local_inspection_plan = inspection_plan;
std::lock_guard<std::mutex> lock(local_waypoint_list_mutex);
local_waypoint_list = waypoint_list;
}
});

Expand All @@ -79,15 +79,15 @@ int main(int, char**)
[&](InspectionBase::Result result, InspectionBase::Ack ack) {
std::cout << RESULT_CONSOLE_TEXT << "Inspection upload result/ack is: " << result
<< " / " << ack << NORMAL_CONSOLE_TEXT << std::endl;
std::lock_guard<std::mutex> lock(local_inspection_mutex);
std::lock_guard<std::mutex> lock(local_waypoint_list_mutex);
inspection_upload = true;
});

std::cout << "Waiting for inspection download..." << std::endl;
for (;;) {
{
std::lock_guard<std::mutex> lock(local_inspection_mutex);
if (local_inspection_plan.inspection_items.size() != 0) {
std::lock_guard<std::mutex> lock(local_waypoint_list_mutex);
if (local_waypoint_list.items.size() != 0) {
std::cout << "Inspection download!" << std::endl;
break;
}
Expand All @@ -97,19 +97,19 @@ int main(int, char**)

{
std::cout << "Modifying local inspection and setting it..." << std::endl;
std::lock_guard<std::mutex> lock(local_inspection_mutex);
local_inspection_plan.inspection_items[0].x = 10.10f;
local_inspection_plan.inspection_items[0].y = 11.11f;
local_inspection_plan.inspection_items[0].z = 12.12f;
inspection_rv.set_upload_inspection(local_inspection_plan);
std::cout << RESULT_CONSOLE_TEXT << local_inspection_plan << NORMAL_CONSOLE_TEXT
std::lock_guard<std::mutex> lock(local_waypoint_list_mutex);
local_waypoint_list.items[0].x = 10.10f;
local_waypoint_list.items[0].y = 11.11f;
local_waypoint_list.items[0].z = 12.12f;
inspection_rv.set_upload_inspection(local_waypoint_list);
std::cout << RESULT_CONSOLE_TEXT << local_waypoint_list << NORMAL_CONSOLE_TEXT
<< std::endl;
}

std::cout << "Waiting for inspection upload..." << std::endl;
for (;;) {
{
std::lock_guard<std::mutex> lock(local_inspection_mutex);
std::lock_guard<std::mutex> lock(local_waypoint_list_mutex);
if (inspection_upload) {
std::cout << "Inspection upload!" << std::endl;
break;
Expand All @@ -123,26 +123,26 @@ int main(int, char**)
inspection_rv.subscribe_inspection_set_current([&](uint16_t seq) {
std::cout << RESULT_CONSOLE_TEXT << "Inspection set current received: " << seq
<< NORMAL_CONSOLE_TEXT << std::endl;
std::lock_guard<std::mutex> lock(local_inspection_mutex);
std::lock_guard<std::mutex> lock(local_waypoint_list_mutex);
inspection_current = seq;
if (inspection_current < local_inspection_plan.inspection_items.size())
if (inspection_current < local_waypoint_list.items.size())
inspection_rv.update_current_inspection_item(inspection_current);
});

{
std::lock_guard<std::mutex> lock(local_inspection_mutex);
if (inspection_current < local_inspection_plan.inspection_items.size())
std::lock_guard<std::mutex> lock(local_waypoint_list_mutex);
if (inspection_current < local_waypoint_list.items.size())
inspection_rv.update_current_inspection_item(inspection_current);
}

// Simulate inspection progress
for (;;) {
sleep_for(seconds(2));

std::lock_guard<std::mutex> lock(local_inspection_mutex);
if (inspection_current < local_inspection_plan.inspection_items.size())
std::lock_guard<std::mutex> lock(local_waypoint_list_mutex);
if (inspection_current < local_waypoint_list.items.size())
inspection_rv.update_reached_inspection_item(inspection_current++);
if (inspection_current < local_inspection_plan.inspection_items.size())
if (inspection_current < local_waypoint_list.items.size())
inspection_rv.update_current_inspection_item(inspection_current);
}

Expand Down
2 changes: 1 addition & 1 deletion src/core/checklist_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ class ChecklistBase {
* @return A reference to the stream.
*/
friend std::ostream&
operator<<(std::ostream& str, ChecklistBase::Checklist const& checklist_plan);
operator<<(std::ostream& str, ChecklistBase::Checklist const& list);

/**
* @brief Possible ACKs returned for action requests.
Expand Down
2 changes: 1 addition & 1 deletion src/core/hl_action_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,7 @@ class HLActionBase {
* @return A reference to the stream.
*/
friend std::ostream&
operator<<(std::ostream& str, HLActionBase::HLActionList const& hl_action_plan);
operator<<(std::ostream& str, HLActionBase::HLActionList const& list);

/**
* @brief Possible ACKs returned for action requests.
Expand Down
56 changes: 28 additions & 28 deletions src/core/inspection_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,9 +5,10 @@
namespace mavsdk {

bool operator==(
const InspectionBase::InspectionItem& lhs, const InspectionBase::InspectionItem& rhs)
const InspectionBase::WaypointItem& lhs, const InspectionBase::WaypointItem& rhs)
{
return (rhs.command == lhs.command) &&
return (rhs.task_id == lhs.task_id) &&
(rhs.command == lhs.command) &&
(rhs.autocontinue == lhs.autocontinue) &&
((std::isnan(rhs.param1) && std::isnan(lhs.param1)) ||
rhs.param1 == lhs.param1) &&
Expand All @@ -25,46 +26,45 @@ bool operator==(
rhs.z == lhs.z);
}

std::ostream& operator<<(std::ostream& str, InspectionBase::InspectionItem const& inspection_item)
std::ostream& operator<<(std::ostream& str, InspectionBase::WaypointItem const& item)
{
str << std::setprecision(15);
str << "inspection_item:\n";
str << "waypoint_item:\n";
str << "{\n";
str << " command: " << inspection_item.command << '\n';
str << " autocontinue: " << unsigned(inspection_item.autocontinue) << '\n';
str << " param1: " << inspection_item.param1 << '\n';
str << " param2: " << inspection_item.param2 << '\n';
str << " param3: " << inspection_item.param3 << '\n';
str << " param4: " << inspection_item.param4 << '\n';
str << " x: " << inspection_item.x << '\n';
str << " y: " << inspection_item.y << '\n';
str << " z: " << inspection_item.z << '\n';
str << " task_id: " << item.task_id << '\n';
str << " command: " << item.command << '\n';
str << " autocontinue: " << unsigned(item.autocontinue) << '\n';
str << " param1: " << item.param1 << '\n';
str << " param2: " << item.param2 << '\n';
str << " param3: " << item.param3 << '\n';
str << " param4: " << item.param4 << '\n';
str << " x: " << item.x << '\n';
str << " y: " << item.y << '\n';
str << " z: " << item.z << '\n';
str << '}';
return str;
}

bool operator==(
const InspectionBase::InspectionPlan& lhs, const InspectionBase::InspectionPlan& rhs)
const InspectionBase::WaypointList& lhs, const InspectionBase::WaypointList& rhs)
{
return (rhs.mission_id == lhs.mission_id) &&
(rhs.inspection_items == lhs.inspection_items);
return rhs.items == lhs.items;
}

std::ostream& operator<<(std::ostream& str, InspectionBase::InspectionPlan const& inspection_plan)
std::ostream& operator<<(std::ostream& str, InspectionBase::WaypointList const& list)
{
str << std::setprecision(15);
str << "inspection_plan:\n";
str << "waypoint_list:\n";
str << "{\n";
str << " mission_id: " << inspection_plan.mission_id << '\n';
str << " inspection_items: [";
if (inspection_plan.inspection_items.size() == 0) {
str << " items: [";
if (list.items.size() == 0) {
str << "]\n";
} else {
for (auto it = inspection_plan.inspection_items.begin();
it != inspection_plan.inspection_items.end();
for (auto it = list.items.begin();
it != list.items.end();
++it) {
str << '\n' << *it;
str << (it + 1 != inspection_plan.inspection_items.end() ? "," : "]\n");
str << (it + 1 != list.items.end() ? "," : "]\n");
}
}
str << '}';
Expand All @@ -78,12 +78,12 @@ bool operator==(
}

std::ostream&
operator<<(std::ostream& str, InspectionBase::InspectionProgress const& inspection_progress)
operator<<(std::ostream& str, InspectionBase::InspectionProgress const& progress)
{
str << std::setprecision(15);
str << "inspection_progress:" << '\n' << "{\n";
str << " current: " << inspection_progress.current << '\n';
str << " reached: " << inspection_progress.reached << '\n';
str << "waypoint_progress:" << '\n' << "{\n";
str << " current: " << progress.current << '\n';
str << " reached: " << progress.reached << '\n';
str << '}';
return str;
}
Expand Down
40 changes: 20 additions & 20 deletions src/core/inspection_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -23,14 +23,15 @@ class InspectionBase {
virtual ~InspectionBase() = default;

/**
* @brief Type representing a inspection item.
* @brief Type representing a waypoint item.
*
* A InspectionItem can contain a position and/or actions.
* Inspection items are building blocks to assemble a inspection,
* A WaypointItem can contain a position and/or actions.
* Waypoint items are building blocks to assemble a inspection,
* which can be sent to (or received from) a system.
* They cannot be used independently.
*/
struct InspectionItem {
struct WaypointItem {
uint32_t task_id{0};
uint16_t command{0};
uint8_t autocontinue{0};
float param1{0};
Expand All @@ -43,51 +44,50 @@ class InspectionBase {
};

/**
* @brief Equal operator to compare two `InspectionBase::InspectionItem` objects.
* @brief Equal operator to compare two `InspectionBase::WaypointItem` objects.
*
* @return `true` if items are equal.
*/
friend bool operator==(
const InspectionBase::InspectionItem& lhs, const InspectionBase::InspectionItem& rhs);
const InspectionBase::WaypointItem& lhs, const InspectionBase::WaypointItem& rhs);

/**
* @brief Stream operator to print information about a `InspectionBase::InspectionItem`.
* @brief Stream operator to print information about a `InspectionBase::WaypointItem`.
*
* @return A reference to the stream.
*/
friend std::ostream&
operator<<(std::ostream& str, InspectionBase::InspectionItem const& inspection_item);
operator<<(std::ostream& str, InspectionBase::WaypointItem const& item);

/**
* @brief Inspection plan type
* @brief Waypoint list
*/
struct InspectionPlan {
uint16_t mission_id{0};
std::vector<InspectionItem> inspection_items{}; /**< @brief The inspection items */
struct WaypointList {
std::vector<WaypointItem> items{}; /**< @brief The waypoint items */
};

/**
* @brief Equal operator to compare two `InspectionBase::InspectionPlan` objects.
* @brief Equal operator to compare two `InspectionBase::WaypointList` objects.
*
* @return `true` if items are equal.
*/
friend bool operator==(
const InspectionBase::InspectionPlan& lhs, const InspectionBase::InspectionPlan& rhs);
const InspectionBase::WaypointList& lhs, const InspectionBase::WaypointList& rhs);

/**
* @brief Stream operator to print information about a `InspectionBase::InspectionPlan`.
* @brief Stream operator to print information about a `InspectionBase::WaypointList`.
*
* @return A reference to the stream.
*/
friend std::ostream&
operator<<(std::ostream& str, InspectionBase::InspectionPlan const& inspection_plan);
operator<<(std::ostream& str, InspectionBase::WaypointList const& list);

/**
* @brief Inspection progress type.
*/
struct InspectionProgress {
int32_t current{}; /**< @brief Current inspection item index (0-based) */
int32_t reached{}; /**< @brief Reached inspection item index (0-based) */
int32_t current{}; /**< @brief Current waypoint item index (0-based) */
int32_t reached{}; /**< @brief Reached waypoint item index (0-based) */
};

/**
Expand All @@ -105,7 +105,7 @@ class InspectionBase {
* @return A reference to the stream.
*/
friend std::ostream&
operator<<(std::ostream& str, InspectionBase::InspectionProgress const& inspection_progress);
operator<<(std::ostream& str, InspectionBase::InspectionProgress const& progress);

/**
* @brief Possible ACKs returned for action requests.
Expand Down Expand Up @@ -169,7 +169,7 @@ class InspectionBase {
/**
* @brief Callback type for download_inspection_async.
*/
using DownloadInspectionCallback = std::function<void(Result, InspectionPlan)>;
using DownloadInspectionCallback = std::function<void(Result, WaypointList)>;

/**
* @brief Callback type for subscribe_inspection_progress.
Expand Down
Loading

0 comments on commit 96d74fd

Please sign in to comment.