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

Consolidate components #2169

Merged
merged 3 commits into from
Dec 17, 2023
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
8 changes: 3 additions & 5 deletions examples/autopilot_server/autopilot_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,8 +59,7 @@ int main(int argc, char** argv)
// thread as a ground station.
std::thread autopilotThread([]() {
mavsdk::Mavsdk mavsdkTester;
mavsdk::Mavsdk::Configuration configuration(
mavsdk::Mavsdk::Configuration::UsageType::Autopilot);
mavsdk::Mavsdk::Configuration configuration(mavsdk::Mavsdk::ComponentType::Autopilot);
mavsdkTester.set_configuration(configuration);

auto result = mavsdkTester.add_any_connection("udp://127.0.0.1:14551");
Expand All @@ -69,7 +68,7 @@ int main(int argc, char** argv)
}

auto server_component =
mavsdkTester.server_component_by_type(Mavsdk::ServerComponentType::Autopilot);
mavsdkTester.server_component_by_type(Mavsdk::ComponentType::Autopilot);

// Create server plugins
auto paramServer = mavsdk::ParamServer{server_component};
Expand Down Expand Up @@ -148,8 +147,7 @@ int main(int argc, char** argv)
// Now this is the main thread, we run client plugins to act as the GCS
// to communicate with the autopilot server plugins.
mavsdk::Mavsdk mavsdk;
mavsdk::Mavsdk::Configuration configuration(
mavsdk::Mavsdk::Configuration::UsageType::GroundStation);
mavsdk::Mavsdk::Configuration configuration(mavsdk::Mavsdk::ComponentType::GroundStation);
mavsdk.set_configuration(configuration);

auto result = mavsdk.add_any_connection("udp://:14551");
Expand Down
3 changes: 1 addition & 2 deletions examples/camera_server/camera_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,7 @@ int main(int argc, const char* argv[])
// we run client plugins to act as the GCS
// to communicate with the camera server plugins.
mavsdk::Mavsdk mavsdk;
mavsdk::Mavsdk::Configuration configuration(
mavsdk::Mavsdk::Configuration::UsageType::GroundStation);
mavsdk::Mavsdk::Configuration configuration(mavsdk::Mavsdk::ComponentType::GroundStation);
mavsdk.set_configuration(configuration);

auto result = mavsdk.add_any_connection("udp://:14030");
Expand Down
4 changes: 2 additions & 2 deletions examples/camera_server/camera_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
int main(int argc, char** argv)
{
mavsdk::Mavsdk mavsdk;
mavsdk::Mavsdk::Configuration configuration(mavsdk::Mavsdk::Configuration::UsageType::Camera);
mavsdk::Mavsdk::Configuration configuration(mavsdk::Mavsdk::ComponentType::Camera);
mavsdk.set_configuration(configuration);

// 14030 is the default camera port for PX4 SITL
Expand All @@ -18,7 +18,7 @@ int main(int argc, char** argv)
std::cout << "Created camera server connection" << std::endl;

auto camera_server = mavsdk::CameraServer{
mavsdk.server_component_by_type(mavsdk::Mavsdk::ServerComponentType::Camera)};
mavsdk.server_component_by_type(mavsdk::Mavsdk::ComponentType::Camera)};

// First add all subscriptions. This defines the camera capabilities.

Expand Down
4 changes: 2 additions & 2 deletions examples/ftp_server/ftp_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ int main(int argc, char** argv)
}

Mavsdk mavsdk;
Mavsdk::Configuration configuration(Mavsdk::Configuration::UsageType::CompanionComputer);
Mavsdk::Configuration configuration(Mavsdk::ComponentType::CompanionComputer);
mavsdk.set_configuration(configuration);
ConnectionResult connection_result = mavsdk.setup_udp_remote(argv[1], std::stoi(argv[2]));
if (connection_result != ConnectionResult::Success) {
Expand All @@ -38,7 +38,7 @@ int main(int argc, char** argv)
}

auto component =
mavsdk.server_component_by_type(mavsdk::Mavsdk::ServerComponentType::CompanionComputer);
mavsdk.server_component_by_type(mavsdk::Mavsdk::ComponentType::CompanionComputer);
auto ftp_server = FtpServer{component};
ftp_server.set_root_dir(argv[3]);

Expand Down
2 changes: 1 addition & 1 deletion examples/gimbal_device_tester/gimbal_device_tester.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -816,7 +816,7 @@ int main(int argc, char** argv)
return 1;
}

Mavsdk::Configuration config(Mavsdk::Configuration::UsageType::Autopilot);
Mavsdk::Configuration config(Mavsdk::ComponentType::Autopilot);
config.set_system_id(own_sysid);
mavsdk.set_configuration(config);

Expand Down
7 changes: 3 additions & 4 deletions src/integration_tests/camera_take_photo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,17 +12,16 @@ TEST(CameraTest, TakePhotoSingle)
{
Mavsdk mavsdk_groundstation;
mavsdk_groundstation.set_configuration(
Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation});
Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation});

Mavsdk mavsdk_camera;
mavsdk_camera.set_configuration(
Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Camera});
mavsdk_camera.set_configuration(Mavsdk::Configuration{Mavsdk::ComponentType::Camera});

ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success);
ASSERT_EQ(mavsdk_camera.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success);

auto camera_server =
CameraServer{mavsdk_camera.server_component_by_type(Mavsdk::ServerComponentType::Camera)};
CameraServer{mavsdk_camera.server_component_by_type(Mavsdk::ComponentType::Camera)};
camera_server.subscribe_take_photo([&camera_server](int32_t index) {
LogInfo() << "Let's take photo " << index;

Expand Down
2 changes: 1 addition & 1 deletion src/integration_tests/connection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ connection_test(const std::string& client_system_address, const std::string& ser
{
// Start instance as a UDP server pretending to be an autopilot
Mavsdk mavsdk_server;
Mavsdk::Configuration config_autopilot(Mavsdk::Configuration::UsageType::Autopilot);
Mavsdk::Configuration config_autopilot(Mavsdk::ComponentType::Autopilot);
mavsdk_server.set_configuration(config_autopilot);
ConnectionResult ret_server = mavsdk_server.add_any_connection(server_system_address);
ASSERT_EQ(ret_server, ConnectionResult::Success);
Expand Down
4 changes: 2 additions & 2 deletions src/integration_tests/statustext.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,12 +16,12 @@ static const auto type = ServerUtility::StatusTextType::Info;
TEST(StatusTextTest, TestServer)
{
Mavsdk mavsdk_gcs;
Mavsdk::Configuration config_gcs(Mavsdk::Configuration::UsageType::GroundStation);
Mavsdk::Configuration config_gcs(Mavsdk::ComponentType::GroundStation);
mavsdk_gcs.set_configuration(config_gcs);
ASSERT_EQ(mavsdk_gcs.add_udp_connection(24550), ConnectionResult::Success);

Mavsdk mavsdk_onboard;
Mavsdk::Configuration config_onboard(Mavsdk::Configuration::UsageType::CompanionComputer);
Mavsdk::Configuration config_onboard(Mavsdk::ComponentType::CompanionComputer);
mavsdk_onboard.set_configuration(config_onboard);
ASSERT_EQ(mavsdk_onboard.setup_udp_remote("127.0.0.1", 24550), ConnectionResult::Success);

Expand Down
57 changes: 23 additions & 34 deletions src/mavsdk/core/include/mavsdk/mavsdk.h
Original file line number Diff line number Diff line change
Expand Up @@ -223,23 +223,23 @@ class Mavsdk {
*/
std::optional<std::shared_ptr<System>> first_autopilot(double timeout_s) const;

/**
* @brief ComponentType of configurations, used for automatic ID setting
*/
enum class ComponentType {
Autopilot, /**< @brief SDK is used as an autopilot. */
GroundStation, /**< @brief SDK is used as a ground station. */
CompanionComputer, /**< @brief SDK is used as a companion computer on board the MAV. */
Camera, /** < @brief SDK is used as a camera. */
Custom /**< @brief the SDK is used in a custom configuration, no automatic ID will be
provided */
};

/**
* @brief Possible configurations.
*/
class Configuration {
public:
/**
* @brief UsageTypes of configurations, used for automatic ID setting
*/
enum class UsageType {
Autopilot, /**< @brief SDK is used as an autopilot. */
GroundStation, /**< @brief SDK is used as a ground station. */
CompanionComputer, /**< @brief SDK is used as a companion computer on board the MAV. */
Camera, /** < @brief SDK is used as a camera. */
Custom /**< @brief the SDK is used in a custom configuration, no automatic ID will be
provided */
};

/**
* @brief Create new Configuration via manually configured
* system and component ID.
Expand All @@ -250,11 +250,11 @@ class Mavsdk {
explicit Configuration(
uint8_t system_id, uint8_t component_id, bool always_send_heartbeats);
/**
* @brief Create new Configuration using a usage type.
* @brief Create new Configuration using a component type.
* In this mode, the system and component ID will be automatically chosen.
* @param usage_type the usage type, used for automatically choosing ids.
* @param component_type the component type, used for automatically choosing ids.
*/
explicit Configuration(UsageType usage_type);
explicit Configuration(ComponentType component_type);

Configuration() = delete;
~Configuration() = default;
Expand Down Expand Up @@ -292,21 +292,21 @@ class Mavsdk {
*/
void set_always_send_heartbeats(bool always_send_heartbeats);

/** @brief Usage type of this configuration, used for automatic ID set */
UsageType get_usage_type() const;
/** @brief Component type of this configuration, used for automatic ID set */
ComponentType get_component_type() const;

/**
* @brief Set the usage type of this configuration.
* @brief Set the component type of this configuration.
*/
void set_usage_type(UsageType usage_type);
void set_component_type(ComponentType component_type);

private:
uint8_t _system_id;
uint8_t _component_id;
bool _always_send_heartbeats;
UsageType _usage_type;
ComponentType _component_type;

static Mavsdk::Configuration::UsageType usage_type_for_component(uint8_t component_id);
static Mavsdk::ComponentType component_type_for_component_id(uint8_t component_id);
};

/**
Expand Down Expand Up @@ -367,30 +367,19 @@ class Mavsdk {
*/
void unsubscribe_on_new_system(NewSystemHandle handle);

/**
* @brief High level type of a server component.
*/
enum class ServerComponentType {
Autopilot, /**< @brief The component identifies as an autopilot. */
GroundStation, /**< @brief The component identifies as a ground station. */
CompanionComputer, /**< @brief The component identifies as a companion computer on board the
system. */
Camera, /** < @brief The component identifies as a camera. */
};

/**
* @brief Get server component by a high level type.
*
* This represents a server component of the MAVSDK instance.
*
* @param server_component_type The high level type of the component.
* @param component_type The high level type of the component.
* @param instance The instance of the component if there are multiple, starting at 0.
*
* @return A valid shared pointer to a server component if it was successful, an empty pointer
* otherwise.
*/
std::shared_ptr<ServerComponent>
server_component_by_type(ServerComponentType server_component_type, unsigned instance = 0);
server_component_by_type(ComponentType component_type, unsigned instance = 0);

/**
* @brief Get server component by the low MAVLink component ID.
Expand Down
2 changes: 1 addition & 1 deletion src/mavsdk/core/lazy_server_plugin.h
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ template<typename ServerPlugin> class LazyServerPlugin {
std::lock_guard<std::mutex> lock(_mutex);
if (_server_plugin == nullptr) {
_server_plugin = std::make_unique<ServerPlugin>(
_mavsdk.server_component_by_type(Mavsdk::ServerComponentType::CompanionComputer));
_mavsdk.server_component_by_type(Mavsdk::ComponentType::CompanionComputer));
}
return _server_plugin.get();
}
Expand Down
39 changes: 19 additions & 20 deletions src/mavsdk/core/mavsdk.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -96,7 +96,7 @@ void Mavsdk::unsubscribe_on_new_system(NewSystemHandle handle)
}

std::shared_ptr<ServerComponent>
Mavsdk::server_component_by_type(ServerComponentType server_component_type, unsigned instance)
Mavsdk::server_component_by_type(ComponentType server_component_type, unsigned instance)
{
return _impl->server_component_by_type(server_component_type, instance);
}
Expand All @@ -111,50 +111,49 @@ Mavsdk::Configuration::Configuration(
_system_id(system_id),
_component_id(component_id),
_always_send_heartbeats(always_send_heartbeats),
_usage_type(usage_type_for_component(component_id))
_component_type(component_type_for_component_id(component_id))
{}

Mavsdk::Configuration::UsageType
Mavsdk::Configuration::usage_type_for_component(uint8_t component_id)
Mavsdk::ComponentType Mavsdk::Configuration::component_type_for_component_id(uint8_t component_id)
{
switch (component_id) {
case MavsdkImpl::DEFAULT_COMPONENT_ID_GCS:
return UsageType::GroundStation;
return ComponentType::GroundStation;
case MavsdkImpl::DEFAULT_COMPONENT_ID_CC:
return UsageType::CompanionComputer;
return ComponentType::CompanionComputer;
case MavsdkImpl::DEFAULT_COMPONENT_ID_AUTOPILOT:
return UsageType::Autopilot;
return ComponentType::Autopilot;
case MavsdkImpl::DEFAULT_COMPONENT_ID_CAMERA:
return UsageType::Camera;
return ComponentType::Camera;
default:
return UsageType::Custom;
return ComponentType::Custom;
}
}

Mavsdk::Configuration::Configuration(UsageType usage_type) :
Mavsdk::Configuration::Configuration(ComponentType component_type) :
_system_id(MavsdkImpl::DEFAULT_SYSTEM_ID_GCS),
_component_id(MavsdkImpl::DEFAULT_COMPONENT_ID_GCS),
_always_send_heartbeats(false),
_usage_type(usage_type)
_component_type(component_type)
{
switch (usage_type) {
case Mavsdk::Configuration::UsageType::GroundStation:
switch (component_type) {
case Mavsdk::ComponentType::GroundStation:
_system_id = MavsdkImpl::DEFAULT_SYSTEM_ID_GCS;
_component_id = MavsdkImpl::DEFAULT_COMPONENT_ID_GCS;
_always_send_heartbeats = false;
break;
case Mavsdk::Configuration::UsageType::CompanionComputer:
case Mavsdk::ComponentType::CompanionComputer:
// TODO implement auto-detection of system ID - maybe from heartbeats?
_system_id = MavsdkImpl::DEFAULT_SYSTEM_ID_CC;
_component_id = MavsdkImpl::DEFAULT_COMPONENT_ID_CC;
_always_send_heartbeats = true;
break;
case Mavsdk::Configuration::UsageType::Autopilot:
case Mavsdk::ComponentType::Autopilot:
_system_id = MavsdkImpl::DEFAULT_SYSTEM_ID_AUTOPILOT;
_component_id = MavsdkImpl::DEFAULT_COMPONENT_ID_AUTOPILOT;
_always_send_heartbeats = true;
break;
case Mavsdk::Configuration::UsageType::Camera:
case Mavsdk::ComponentType::Camera:
_system_id = MavsdkImpl::DEFAULT_SYSTEM_ID_CAMERA;
_component_id = MavsdkImpl::DEFAULT_COMPONENT_ID_CAMERA;
_always_send_heartbeats = true;
Expand Down Expand Up @@ -194,14 +193,14 @@ void Mavsdk::Configuration::set_always_send_heartbeats(bool always_send_heartbea
_always_send_heartbeats = always_send_heartbeats;
}

Mavsdk::Configuration::UsageType Mavsdk::Configuration::get_usage_type() const
Mavsdk::ComponentType Mavsdk::Configuration::get_component_type() const
{
return _usage_type;
return _component_type;
}

void Mavsdk::Configuration::set_usage_type(Mavsdk::Configuration::UsageType usage_type)
void Mavsdk::Configuration::set_component_type(Mavsdk::ComponentType component_type)
{
_usage_type = usage_type;
_component_type = component_type;
}

void Mavsdk::intercept_incoming_messages_async(std::function<bool(mavlink_message_t&)> callback)
Expand Down
Loading