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

Remove MAVLink gimbal v1 protocol #2361

Merged
merged 2 commits into from
Jul 29, 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
16 changes: 3 additions & 13 deletions examples/gimbal_full_control/gimbal_full_control.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,6 @@
#include <cstdint>
#include <mavsdk/mavsdk.h>
#include <mavsdk/plugins/gimbal/gimbal.h>
#include <mavsdk/plugins/telemetry/telemetry.h>
#include <iostream>
#include <future>
#include <memory>
Expand Down Expand Up @@ -50,20 +49,11 @@ int main(int argc, char** argv)
}

// Instantiate plugins.
auto telemetry = Telemetry{system.value()};
auto gimbal = Gimbal{system.value()};

// We want to listen to the camera/gimbal angle of the drone at 5 Hz.
const Telemetry::Result set_rate_result = telemetry.set_rate_camera_attitude(5.0);
if (set_rate_result != Telemetry::Result::Success) {
std::cerr << "Setting rate failed:" << set_rate_result << '\n';
return 1;
}

// Set up callback to monitor camera/gimbal angle
telemetry.subscribe_camera_attitude_euler([](Telemetry::EulerAngle angle) {
std::cout << "Gimbal angle pitch: " << angle.pitch_deg << " deg, yaw: " << angle.yaw_deg
<< " deg, roll: " << angle.roll_deg << " deg\n";
gimbal.subscribe_attitude([](Gimbal::Attitude attitude) {
std::cout << "Gimbal angle pitch: " << attitude.euler_angle_forward.pitch_deg
<< " deg, yaw: " << attitude.euler_angle_forward.yaw_deg << " deg\n";
});

std::cout << "Start controlling gimbal...\n";
Expand Down
2 changes: 1 addition & 1 deletion proto
40 changes: 0 additions & 40 deletions src/integration_tests/telemetry_async.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,6 @@
#include "mavsdk.h"
#include "plugins/telemetry/telemetry.h"

#define CAMERA_AVAILABLE 0 // Set to 1 if camera is available and should be tested.

using namespace mavsdk;

static void receive_result(Telemetry::Result result);
Expand All @@ -19,10 +17,6 @@ static void print_euler_angle(Telemetry::EulerAngle euler_angle);
static void print_angular_velocity_body(Telemetry::AngularVelocityBody angular_velocity_body);
static void print_fixedwing_metrics(Telemetry::FixedwingMetrics fixedwing_metrics);
static void print_ground_truth(const Telemetry::GroundTruth& ground_truth);
#if CAMERA_AVAILABLE == 1
static void print_camera_quaternion(Telemetry::Quaternion quaternion);
static void print_camera_euler_angle(Telemetry::EulerAngle euler_angle);
#endif
static void print_velocity_ned(Telemetry::VelocityNed velocity_ned);
static void print_imu(Telemetry::Imu imu);
static void print_gps_info(Telemetry::GpsInfo gps_info);
Expand All @@ -44,10 +38,6 @@ static bool _received_euler_angle = false;
static bool _received_angular_velocity_body = false;
static bool _received_fixedwing_metrics = false;
static bool _received_ground_truth = false;
#if CAMERA_AVAILABLE == 1
static bool _received_camera_quaternion = false;
static bool _received_camera_euler_angle = false;
#endif
static bool _received_velocity = false;
static bool _received_imu = false;
static bool _received_gps_info = false;
Expand Down Expand Up @@ -153,14 +143,6 @@ TEST(SitlTest, PX4TelemetryAsync)
telemetry->subscribe_ground_truth(
[](Telemetry::GroundTruth ground_truth) { print_ground_truth(ground_truth); });

#if CAMERA_AVAILABLE == 1
telemetry->subscribe_camera_attitude_quaternion(
[](Telemetry::Quaternion quaternion) { print_camera_quaternion(quaternion); });

telemetry->subscribe_camera_attitude_euler(
[](Telemetry::EulerAngle euler_angle) { print_camera_euler_angle(euler_angle); });
#endif

telemetry->subscribe_velocity_ned(
[](Telemetry::VelocityNed velocity_ned) { print_velocity_ned(velocity_ned); });

Expand Down Expand Up @@ -206,10 +188,6 @@ TEST(SitlTest, PX4TelemetryAsync)
EXPECT_TRUE(_received_fixedwing_metrics);
EXPECT_TRUE(_received_ground_truth);
EXPECT_TRUE(_received_euler_angle);
#if CAMERA_AVAILABLE == 1
EXPECT_TRUE(_received_camera_quaternion);
EXPECT_TRUE(_received_camera_euler_angle);
#endif
EXPECT_TRUE(_received_velocity);
EXPECT_TRUE(_received_imu);
EXPECT_TRUE(_received_gps_info);
Expand Down Expand Up @@ -297,24 +275,6 @@ void print_ground_truth(const Telemetry::GroundTruth& ground_truth)
_received_ground_truth = true;
}

#if CAMERA_AVAILABLE == 1
void print_camera_quaternion(Telemetry::Quaternion quaternion)
{
std::cout << "Camera Quaternion: [ " << quaternion.w << ", " << quaternion.x << ", "
<< quaternion.y << ", " << quaternion.z << " ]" << '\n';

_received_camera_quaternion = true;
}

void print_camera_euler_angle(Telemetry::EulerAngle euler_angle)
{
std::cout << "Camera Euler angle: [ " << euler_angle.roll_deg << ", " << euler_angle.pitch_deg
<< ", " << euler_angle.yaw_deg << " ] deg" << '\n';

_received_camera_euler_angle = true;
}
#endif

void print_velocity_ned(Telemetry::VelocityNed velocity_ned)
{
std::cout << "Ground speed NED: [ " << velocity_ned.north_m_s << ", " << velocity_ned.east_m_s
Expand Down
2 changes: 0 additions & 2 deletions src/mavsdk/plugins/gimbal/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,6 @@ target_sources(mavsdk
PRIVATE
gimbal.cpp
gimbal_impl.cpp
gimbal_protocol_v1.cpp
gimbal_protocol_v2.cpp
)

target_include_directories(mavsdk PUBLIC
Expand Down
Loading
Loading