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

Change connection CLI, add TCP server connections #2342

Merged
merged 17 commits into from
Jul 22, 2024
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
19 changes: 8 additions & 11 deletions examples/ftp_server/ftp_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,34 +15,31 @@ using namespace mavsdk;

void usage(const std::string& bin_name)
{
std::cerr << "Usage : " << bin_name << " <remote_ip> <remote_port> <root_dir>\n"
<< '\n'
<< " Start mavlink FTP server on <root_dir>\n"
<< " sending heartbeats to <remote_ip>:<remote_port>\n";
std::cerr << "Usage : " << bin_name << " <connection> <root_dir>" << std::endl;
}

int main(int argc, char** argv)
{
if (argc != 4) {
if (argc != 3) {
usage(argv[0]);
return 1;
}

Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::CompanionComputer}};
ConnectionResult connection_result = mavsdk.setup_udp_remote(argv[1], std::stoi(argv[2]));
ConnectionResult connection_result = mavsdk.add_any_connection(argv[1]);
if (connection_result != ConnectionResult::Success) {
std::cerr << "Error setting up Mavlink FTP server.\n";
return 1;
}

auto component = mavsdk.server_component();
auto ftp_server = FtpServer{component};
ftp_server.set_root_dir(argv[3]);
ftp_server.set_root_dir(argv[2]);

std::cout << "Mavlink FTP server running.\n"
<< '\n'
<< "Remote: " << argv[1] << ":" << argv[2] << '\n'
<< "Component ID: " << std::to_string(component->component_id()) << '\n';
std::cout << "MAVLink FTP server running\n"
<< " connection: " << argv[1] << '\n'
<< " directory: " << argv[2] << '\n'
<< " component ID: " << std::to_string(component->component_id()) << std::endl;

while (true) {
std::this_thread::sleep_for(std::chrono::seconds(1));
Expand Down
2 changes: 1 addition & 1 deletion src/integration_tests/action_goto.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ TEST(SitlTest, PX4ActionGoto)
{
Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}};

ConnectionResult ret = mavsdk.add_udp_connection();
ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540");
ASSERT_EQ(ret, ConnectionResult::Success);

// Wait for system to connect via heartbeat.
Expand Down
2 changes: 1 addition & 1 deletion src/integration_tests/action_hold.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ TEST(SitlTest, PX4ActionHold)
{
Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}};

ConnectionResult ret = mavsdk.add_udp_connection();
ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540");
ASSERT_EQ(ret, ConnectionResult::Success);

// Wait for system to connect via heartbeat.
Expand Down
2 changes: 1 addition & 1 deletion src/integration_tests/action_hover_async.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ TEST(SitlTest, ActionHoverAsync)
{
Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}};

ConnectionResult ret = mavsdk.add_udp_connection();
ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540");
ASSERT_EQ(ret, ConnectionResult::Success);

auto system = std::shared_ptr<System>{nullptr};
Expand Down
4 changes: 2 additions & 2 deletions src/integration_tests/action_hover_sync.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ void takeoff_and_hover_at_altitude(float altitude_m)
{
Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}};

ConnectionResult ret = mavsdk.add_udp_connection();
ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540");
ASSERT_EQ(ret, ConnectionResult::Success);

// Wait for system to connect via heartbeat.
Expand Down Expand Up @@ -125,7 +125,7 @@ void takeoff_and_hover_at_altitude_apm(float altitude_m)
{
Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}};

ConnectionResult ret = mavsdk.add_udp_connection();
ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540");
ASSERT_EQ(ret, ConnectionResult::Success);

// Wait for system to connect via heartbeat.
Expand Down
2 changes: 1 addition & 1 deletion src/integration_tests/action_takeoff_and_kill.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ using namespace mavsdk;
TEST(SitlTest, ActionTakeoffAndKill)
{
Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}};
ASSERT_EQ(mavsdk.add_udp_connection(), ConnectionResult::Success);
ASSERT_EQ(mavsdk.add_any_connection("udpin://0.0.0.0:14540"), ConnectionResult::Success);

{
LogInfo() << "Waiting to discover vehicle";
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ TEST(SitlTest, PX4ActionTransitionSync_standard_vtol)
// Init & connect
Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}};

ConnectionResult ret = mavsdk.add_udp_connection();
ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540");
ASSERT_EQ(ret, ConnectionResult::Success);

// Wait for system to connect via heartbeat.
Expand Down
14 changes: 7 additions & 7 deletions src/integration_tests/calibration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ TEST(HardwareTest, CalibrationGyro)
{
Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}};

ConnectionResult ret = mavsdk.add_udp_connection();
ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540");
ASSERT_EQ(ret, ConnectionResult::Success);

// Wait for system to connect via heartbeat.
Expand Down Expand Up @@ -47,7 +47,7 @@ TEST(HardwareTest, CalibrationAccelerometer)
{
Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}};

ConnectionResult ret = mavsdk.add_udp_connection();
ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540");
ASSERT_EQ(ret, ConnectionResult::Success);

// Wait for system to connect via heartbeat.
Expand Down Expand Up @@ -76,7 +76,7 @@ TEST(HardwareTest, CalibrationMagnetometer)
{
Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}};

ConnectionResult ret = mavsdk.add_udp_connection();
ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540");
ASSERT_EQ(ret, ConnectionResult::Success);

// Wait for system to connect via heartbeat.
Expand Down Expand Up @@ -105,7 +105,7 @@ TEST(HardwareTest, CalibrationLevelHorizon)
{
Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}};

ConnectionResult ret = mavsdk.add_udp_connection();
ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540");
ASSERT_EQ(ret, ConnectionResult::Success);

// Wait for system to connect via heartbeat.
Expand Down Expand Up @@ -134,7 +134,7 @@ TEST(HardwareTest, CalibrationGimbalAccelerometer)
{
Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}};

ConnectionResult ret = mavsdk.add_udp_connection();
ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540");
ASSERT_EQ(ret, ConnectionResult::Success);

// Wait for system to connect via heartbeat.
Expand Down Expand Up @@ -163,7 +163,7 @@ TEST(HardwareTest, CalibrationGyroWithTelemetry)
{
Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}};

ConnectionResult ret = mavsdk.add_udp_connection();
ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540");
ASSERT_EQ(ret, ConnectionResult::Success);

// Wait for system to connect via heartbeat.
Expand Down Expand Up @@ -206,7 +206,7 @@ TEST(HardwareTest, CalibrationGyroCancelled)
{
Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}};

ConnectionResult ret = mavsdk.add_udp_connection();
ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540");
ASSERT_EQ(ret, ConnectionResult::Success);

// Wait for system to connect via heartbeat.
Expand Down
2 changes: 1 addition & 1 deletion src/integration_tests/camera_capture_info.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ TEST(CameraTest, CaptureInfo)
{
Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}};

ConnectionResult ret = mavsdk.add_udp_connection();
ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540");
ASSERT_EQ(ret, ConnectionResult::Success);

// Wait for system to connect via heartbeat.
Expand Down
2 changes: 1 addition & 1 deletion src/integration_tests/camera_format.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ TEST(CameraTest, Format)
{
Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}};

ConnectionResult ret = mavsdk.add_udp_connection();
ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540");
ASSERT_EQ(ret, ConnectionResult::Success);

// Wait for system to connect via heartbeat.
Expand Down
4 changes: 2 additions & 2 deletions src/integration_tests/camera_mode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ TEST(CameraTest, SetModeSync)
{
Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}};

ConnectionResult ret = mavsdk.add_udp_connection();
ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540");
ASSERT_EQ(ret, ConnectionResult::Success);

// Wait for system to connect via heartbeat.
Expand Down Expand Up @@ -50,7 +50,7 @@ TEST(CameraTest, SetModeAsync)
{
Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}};

ConnectionResult ret = mavsdk.add_udp_connection();
ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540");
ASSERT_EQ(ret, ConnectionResult::Success);

// Wait for system to connect via heartbeat.
Expand Down
2 changes: 1 addition & 1 deletion src/integration_tests/camera_reset_settings.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ TEST(CameraTest, ResetSettings)
{
Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}};

ConnectionResult ret = mavsdk.add_udp_connection();
ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540");
ASSERT_EQ(ret, ConnectionResult::Success);

// Wait for system to connect via heartbeat.
Expand Down
8 changes: 4 additions & 4 deletions src/integration_tests/camera_settings.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ TEST(CameraTest, ShowSettingsAndOptions)
{
Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}};

ConnectionResult ret = mavsdk.add_udp_connection();
ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540");
ASSERT_EQ(ret, ConnectionResult::Success);

// Wait for system to connect via heartbeat.
Expand Down Expand Up @@ -127,7 +127,7 @@ TEST(CameraTest, SetSettings)
{
Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}};

ConnectionResult connection_ret = mavsdk.add_udp_connection();
ConnectionResult connection_ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540");
ASSERT_EQ(connection_ret, ConnectionResult::Success);

// Wait for system to connect via heartbeat.
Expand Down Expand Up @@ -265,7 +265,7 @@ TEST(CameraTest, SubscribeCurrentSettings)
{
Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}};

ConnectionResult connection_ret = mavsdk.add_udp_connection();
ConnectionResult connection_ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540");
ASSERT_EQ(connection_ret, ConnectionResult::Success);

// Wait for system to connect via heartbeat.
Expand Down Expand Up @@ -329,7 +329,7 @@ TEST(CameraTest, SubscribePossibleSettings)
{
Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}};

ConnectionResult connection_ret = mavsdk.add_udp_connection();
ConnectionResult connection_ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540");
ASSERT_EQ(connection_ret, ConnectionResult::Success);

// Wait for system to connect via heartbeat.
Expand Down
2 changes: 1 addition & 1 deletion src/integration_tests/camera_status.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ TEST(CameraTest, Status)
{
Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}};

ConnectionResult ret = mavsdk.add_udp_connection();
ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540");
ASSERT_EQ(ret, ConnectionResult::Success);

// Wait for system to connect via heartbeat.
Expand Down
2 changes: 1 addition & 1 deletion src/integration_tests/camera_take_photo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ TEST(CameraTest, TakePhotosMultiple)

const int num_photos_to_take = 3;

ConnectionResult ret = mavsdk.add_udp_connection();
ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540");
ASSERT_EQ(ret, ConnectionResult::Success);

// Wait for system to connect via heartbeat.
Expand Down
2 changes: 1 addition & 1 deletion src/integration_tests/camera_take_photo_interval.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ TEST(CameraTest, TakePhotoInterval)
{
Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}};

ConnectionResult ret = mavsdk.add_udp_connection();
ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540");
ASSERT_EQ(ret, ConnectionResult::Success);

// Wait for system to connect via heartbeat.
Expand Down
4 changes: 2 additions & 2 deletions src/integration_tests/follow_me.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ TEST(SitlTest, PX4FollowMeOneLocation)
{
Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}};

ConnectionResult ret = mavsdk.add_udp_connection();
ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540");
ASSERT_EQ(ConnectionResult::Success, ret);

// Wait for system to connect via heartbeat.
Expand Down Expand Up @@ -116,7 +116,7 @@ TEST(SitlTest, PX4FollowMeMultiLocationWithConfig)
{
Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}};

ConnectionResult ret = mavsdk.add_udp_connection();
ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540");
ASSERT_EQ(ConnectionResult::Success, ret);

// Wait for system to connect via heartbeat.
Expand Down
2 changes: 1 addition & 1 deletion src/integration_tests/geofence.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ TEST(SitlTest, PX4GeofenceInclusion)
{
Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}};

ConnectionResult ret = mavsdk.add_udp_connection();
ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540");
ASSERT_EQ(ret, ConnectionResult::Success);

// Wait for system to connect via heartbeat.
Expand Down
8 changes: 4 additions & 4 deletions src/integration_tests/gimbal.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ TEST(SitlTestGimbal, GimbalMove)
{
Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}};

ConnectionResult ret = mavsdk.add_udp_connection();
ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540");
ASSERT_EQ(ret, ConnectionResult::Success);

// Wait for system to connect via heartbeat.
Expand Down Expand Up @@ -74,7 +74,7 @@ TEST(SitlTestGimbal, GimbalAngles)
{
Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}};

ConnectionResult ret = mavsdk.add_udp_connection();
ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540");
ASSERT_EQ(ret, ConnectionResult::Success);

// Wait for system to connect via heartbeat.
Expand Down Expand Up @@ -126,7 +126,7 @@ TEST(SitlTestGimbal, GimbalTakeoffAndMove)
{
Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}};

ConnectionResult ret = mavsdk.add_udp_connection();
ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540");
ASSERT_EQ(ret, ConnectionResult::Success);

// Wait for system to connect via heartbeat.
Expand Down Expand Up @@ -240,7 +240,7 @@ TEST(SitlTestGimbal, GimbalROIOffboard)
{
Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}};

ConnectionResult ret = mavsdk.add_udp_connection();
ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540");
ASSERT_EQ(ret, ConnectionResult::Success);

// Wait for system to connect via heartbeat.
Expand Down
2 changes: 1 addition & 1 deletion src/integration_tests/info.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ TEST(SitlTest, PX4Info)
{
Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}};

ConnectionResult ret = mavsdk.add_udp_connection();
ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540");
ASSERT_EQ(ret, ConnectionResult::Success);

// Wait for system to connect via heartbeat.
Expand Down
6 changes: 3 additions & 3 deletions src/integration_tests/log_files.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ TEST(HardwareTest, LogFiles)
Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}};

// ConnectionResult ret = mavsdk.add_serial_connection("/dev/ttyACM0");
ConnectionResult ret = mavsdk.add_udp_connection();
ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540");
ASSERT_EQ(ret, ConnectionResult::Success);

std::this_thread::sleep_for(std::chrono::seconds(2));
Expand Down Expand Up @@ -69,7 +69,7 @@ TEST(HardwareTest, LogFilesDownloadFailsIfPathIsDirectory)
Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}};

// ConnectionResult ret = mavsdk.add_serial_connection("/dev/ttyACM0");
ConnectionResult ret = mavsdk.add_udp_connection();
ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540");
ASSERT_EQ(ret, ConnectionResult::Success);

std::this_thread::sleep_for(std::chrono::seconds(2));
Expand Down Expand Up @@ -125,7 +125,7 @@ TEST(HardwareTest, LogFilesDownloadFailsIfFileAlreadyExists)
Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}};

// ConnectionResult ret = mavsdk.add_serial_connection("/dev/ttyACM0");
ConnectionResult ret = mavsdk.add_udp_connection();
ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540");
ASSERT_EQ(ret, ConnectionResult::Success);

std::this_thread::sleep_for(std::chrono::seconds(2));
Expand Down
2 changes: 1 addition & 1 deletion src/integration_tests/logging.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ TEST(SitlTest, PX4Logging)
{
Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}};

ConnectionResult ret = mavsdk.add_udp_connection();
ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540");
ASSERT_EQ(ret, ConnectionResult::Success);

std::this_thread::sleep_for(std::chrono::seconds(2));
Expand Down
2 changes: 1 addition & 1 deletion src/integration_tests/mavlink_passthrough.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ using namespace mavsdk;
TEST(SitlTest, PX4MavlinkPassthrough)
{
Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}};
ASSERT_EQ(mavsdk.add_udp_connection(), ConnectionResult::Success);
ASSERT_EQ(mavsdk.add_any_connection("udpin://0.0.0.0:14540"), ConnectionResult::Success);

{
LogInfo() << "Waiting to discover vehicle";
Expand Down
Loading
Loading