Skip to content

Commit

Permalink
core, integration_tests: Address review comments (mavlink#310)
Browse files Browse the repository at this point in the history
1. Corrected and improved `MAVLinkSystem::has_camera()` logic.
2. Use default initializer for `camera_ids` vector.
3. Add description for GCS.
4. Replace `is_autopilot()` to `has_autopilot()`.
5. Correct API descriptions of `has_camera()`, `has_gimbal()`, `has_autopilot()`.
6. Move friend decl to private of class `System` and describe them.
7. Necessary modifications in `SitlTest.MultiComponentDiscovery` test.
  • Loading branch information
Shakthi Prashanth M committed Apr 4, 2018
1 parent 834218d commit 6b1391c
Show file tree
Hide file tree
Showing 5 changed files with 58 additions and 33 deletions.
35 changes: 28 additions & 7 deletions core/mavlink_system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -334,20 +334,42 @@ size_t MAVLinkSystem::total_components() const

bool MAVLinkSystem::is_standalone() const
{
return !is_autopilot();
return !has_autopilot();
}

bool MAVLinkSystem::is_autopilot() const
bool MAVLinkSystem::has_autopilot() const
{
return get_autopilot_id() != uint8_t(0);
}

bool MAVLinkSystem::is_autopilot(uint8_t comp_id)
{
return comp_id == MAV_COMP_ID_AUTOPILOT1;
}

bool MAVLinkSystem::is_camera(uint8_t comp_id)
{
return (comp_id >= MAV_COMP_ID_CAMERA)
&& (comp_id <= MAV_COMP_ID_CAMERA6);
}

bool MAVLinkSystem::has_camera(uint8_t camera_id) const
{
uint8_t camera_comp_id = MAV_COMP_ID_CAMERA + (camera_id - 1);
uint8_t camera_comp_id = (camera_id == 0) ?
camera_id : (MAV_COMP_ID_CAMERA + (camera_id - 1));

for (auto compid : _components) {
return compid == camera_comp_id;
if (camera_comp_id == 0) { // Check whether the system has any camera.
for (auto compid : _components) {
if (is_camera(compid)) {
return true;
}
}
} else { // Look for the camera whose id is `camera_id`.
for (auto compid : _components) {
if (compid == camera_comp_id) {
return true;
}
}
}
return false;
}
Expand Down Expand Up @@ -687,8 +709,7 @@ uint8_t MAVLinkSystem::get_autopilot_id() const

std::vector<uint8_t> MAVLinkSystem::get_camera_ids() const
{
std::vector<uint8_t> camera_ids;
camera_ids.clear();
std::vector<uint8_t> camera_ids {};

for (auto compid : _components)
if (compid >= MAV_COMP_ID_CAMERA && compid <= MAV_COMP_ID_CAMERA6) {
Expand Down
11 changes: 7 additions & 4 deletions core/mavlink_system.h
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,8 @@ class DroneCoreImpl;
class PluginImplBase;


// This represents DroneCore client application which is a GCS.
// GCS: Ground Control Station
// Type that represents DroneCore client application which is a GCS.
struct GCSClient {
static constexpr uint8_t system_id = 0;
static constexpr uint8_t component_id = MAV_COMP_ID_SYSTEM_CONTROL;
Expand Down Expand Up @@ -102,8 +103,8 @@ class MAVLinkSystem
uint8_t get_gimbal_id() const;

bool is_standalone() const;
bool is_autopilot() const;
bool has_camera(uint8_t camera_id = 1) const;
bool has_autopilot() const;
bool has_camera(uint8_t camera_id = 0) const;
bool has_gimbal() const;

uint64_t get_uuid() const;
Expand Down Expand Up @@ -151,7 +152,9 @@ class MAVLinkSystem
private:

// Helper methods added to increase readablity
bool is_autopilot(uint8_t comp_id) const { return comp_id == MAV_COMP_ID_AUTOPILOT1; }
static bool is_autopilot(uint8_t comp_id);
static bool is_camera(uint8_t comp_id);

bool have_uuid() const { return _uuid != 0 && _uuid_initialized; }

void process_heartbeat(const mavlink_message_t &message);
Expand Down
7 changes: 4 additions & 3 deletions core/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,8 @@ System::System(DroneCoreImpl &parent,
uint8_t component_id)
{
_mavlink_system = std::make_shared<MAVLinkSystem>(parent,
system_id, component_id);
system_id,
component_id);
}

System::~System()
Expand All @@ -32,9 +33,9 @@ bool System::is_standalone() const
return _mavlink_system->is_standalone();
}

bool System::is_autopilot() const
bool System::has_autopilot() const
{
return _mavlink_system->is_autopilot();
return _mavlink_system->has_autopilot();
}

bool System::has_camera(uint8_t camera_id) const
Expand Down
23 changes: 15 additions & 8 deletions core/system.h
Original file line number Diff line number Diff line change
Expand Up @@ -21,10 +21,10 @@ class System
~System();

/**
* @brief Checks whether the system is an autopilot.
* @brief Checks whether the system has an autopilot.
* @return true if its an autopilot, false otherwise.
*/
bool is_autopilot() const;
bool has_autopilot() const;

/**
* @brief Checks whether the system is a standalone (Non-autopilot).
Expand All @@ -33,23 +33,22 @@ class System
bool is_standalone() const;

/**
* @brief Checks whether the system has camera with the given camera ID.
* @brief Checks whether the system has a camera with the given camera ID.
*
* A System may have several cameras with ID starting from 1.
* When called without passing camera ID, it checks for the camera ID 1.
* When called without passing camera ID, it checks whether the system has
* any camera.
* @param camera_id ID of the camera starting from 1 onwards.
* @return true if camera with the given camera ID is found, false otherwise.
*/
bool has_camera(uint8_t camera_id = 1) const;
bool has_camera(uint8_t camera_id = 0) const;

/**
* @brief Checks whether the system has gimbal.
* @brief Checks whether the system has a gimbal.
* @return true if the system has gimbal, false otherwise.
*/
bool has_gimbal() const;

friend class DroneCoreImpl;
friend class PluginImplBase;

// Non-copyable
System(const System &) = delete;
Expand All @@ -66,6 +65,14 @@ class System

std::shared_ptr<MAVLinkSystem> mavlink_system() { return _mavlink_system; };

/* TODO: Optimize this later.
* For now,
* - DroneCoreImpl wants to access private methods of System.
* - PluginImplBase requests System class to get instance of MAVLinkSystem class.
*/
friend DroneCoreImpl;
friend PluginImplBase;

std::shared_ptr<MAVLinkSystem> _mavlink_system;
};

Expand Down
15 changes: 4 additions & 11 deletions integration_tests/multi_components.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,23 +42,16 @@ TEST_F(SitlTest, MultiComponentDiscovery)
std::cout << "We found a System with UUID: " << uuid << '\n';
System &system = dc.system(uuid);

auto is_autopilot = system.is_autopilot();

auto has_autopilot = system.has_autopilot();
auto is_standalone = system.is_standalone();

auto has_camera = system.has_camera(); // by default checks for camera 1
if (has_camera) {
has_camera = system.has_camera(1); // pass camera ID explcitly
EXPECT_EQ(has_camera, true);
}

auto has_camera = system.has_camera(); // Checks whether the system has any camera
auto has_gimbal = system.has_gimbal();

if (is_autopilot && has_camera && !has_gimbal) {
if (has_autopilot && has_camera && !has_gimbal) {
std::cout << "Its an Autopilot with a Camera." << '\n';
} else if (is_standalone && has_camera) {
std::cout << "Its a Standalone camera." << '\n';
} else if (is_autopilot && !has_camera) {
} else if (has_autopilot && !has_camera) {
std::cout << "Its an Autopilot alone." << '\n';
}
}
Expand Down

0 comments on commit 6b1391c

Please sign in to comment.