Skip to content

Commit

Permalink
telemetry: remove camera attitude
Browse files Browse the repository at this point in the history
This is better covered by the gimbal plugin.
  • Loading branch information
julianoes committed Jul 29, 2024
1 parent 03a8034 commit e64553a
Show file tree
Hide file tree
Showing 14 changed files with 8,276 additions and 12,851 deletions.
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
77 changes: 3 additions & 74 deletions src/mavsdk/plugins/telemetry/include/plugins/telemetry/telemetry.h
Original file line number Diff line number Diff line change
Expand Up @@ -1266,62 +1266,6 @@ class Telemetry : public PluginBase {
*/
AngularVelocityBody attitude_angular_velocity_body() const;

/**
* @brief Callback type for subscribe_camera_attitude_quaternion.
*/
using CameraAttitudeQuaternionCallback = std::function<void(Quaternion)>;

/**
* @brief Handle type for subscribe_camera_attitude_quaternion.
*/
using CameraAttitudeQuaternionHandle = Handle<Quaternion>;

/**
* @brief Subscribe to 'camera attitude' updates (quaternion).
*/
CameraAttitudeQuaternionHandle
subscribe_camera_attitude_quaternion(const CameraAttitudeQuaternionCallback& callback);

/**
* @brief Unsubscribe from subscribe_camera_attitude_quaternion
*/
void unsubscribe_camera_attitude_quaternion(CameraAttitudeQuaternionHandle handle);

/**
* @brief Poll for 'Quaternion' (blocking).
*
* @return One Quaternion update.
*/
Quaternion camera_attitude_quaternion() const;

/**
* @brief Callback type for subscribe_camera_attitude_euler.
*/
using CameraAttitudeEulerCallback = std::function<void(EulerAngle)>;

/**
* @brief Handle type for subscribe_camera_attitude_euler.
*/
using CameraAttitudeEulerHandle = Handle<EulerAngle>;

/**
* @brief Subscribe to 'camera attitude' updates (Euler).
*/
CameraAttitudeEulerHandle
subscribe_camera_attitude_euler(const CameraAttitudeEulerCallback& callback);

/**
* @brief Unsubscribe from subscribe_camera_attitude_euler
*/
void unsubscribe_camera_attitude_euler(CameraAttitudeEulerHandle handle);

/**
* @brief Poll for 'EulerAngle' (blocking).
*
* @return One EulerAngle update.
*/
EulerAngle camera_attitude_euler() const;

/**
* @brief Callback type for subscribe_velocity_ned.
*/
Expand Down Expand Up @@ -2064,30 +2008,15 @@ class Telemetry : public PluginBase {

/**
* @brief Set rate of camera attitude updates.
*
* This function is non-blocking. See 'set_rate_camera_attitude' for the blocking counterpart.
*/
void set_rate_camera_attitude_async(double rate_hz, const ResultCallback callback);

/**
* @brief Set rate of camera attitude updates.
*
* This function is blocking. See 'set_rate_camera_attitude_async' for the non-blocking
* counterpart.
*
* @return Result of request.
*/
Result set_rate_camera_attitude(double rate_hz) const;

/**
* @brief Set rate to 'ground speed' updates (NED).
* Set rate to 'ground speed' updates (NED).
*
* This function is non-blocking. See 'set_rate_velocity_ned' for the blocking counterpart.
*/
void set_rate_velocity_ned_async(double rate_hz, const ResultCallback callback);

/**
* @brief Set rate to 'ground speed' updates (NED).
* @brief Set rate of camera attitude updates.
* Set rate to 'ground speed' updates (NED).
*
* This function is blocking. See 'set_rate_velocity_ned_async' for the non-blocking
* counterpart.
Expand Down
11 changes: 0 additions & 11 deletions src/mavsdk/plugins/telemetry/mocks/telemetry_mock.h
Original file line number Diff line number Diff line change
Expand Up @@ -51,15 +51,6 @@ class MockTelemetry {
subscribe_attitude_euler,
Telemetry::AttitudeEulerHandle(Telemetry::AttitudeEulerCallback)){};
MOCK_CONST_METHOD1(unsubscribe_attitude_euler, void(Telemetry::AttitudeEulerHandle)){};
MOCK_CONST_METHOD1(
subscribe_camera_attitude_quaternion,
Telemetry::AttitudeQuaternionHandle(Telemetry::AttitudeQuaternionCallback)){};
MOCK_CONST_METHOD1(
unsubscribe_camera_attitude_quaternion, void(Telemetry::AttitudeQuaternionHandle)){};
MOCK_CONST_METHOD1(
subscribe_camera_attitude_euler,
Telemetry::AttitudeEulerHandle(Telemetry::AttitudeEulerCallback)){};
MOCK_CONST_METHOD1(unsubscribe_camera_attitude_euler, void(Telemetry::AttitudeEulerHandle)){};
MOCK_CONST_METHOD1(
subscribe_velocity_ned, Telemetry::VelocityNedHandle(Telemetry::VelocityNedCallback)){};
MOCK_CONST_METHOD1(unsubscribe_velocity_ned, void(Telemetry::VelocityNedHandle)){};
Expand Down Expand Up @@ -125,7 +116,6 @@ class MockTelemetry {
MOCK_METHOD1(set_rate_landed_state, Telemetry::Result(double)){};
MOCK_METHOD1(set_rate_attitude_quaternion, Telemetry::Result(double)){};
MOCK_METHOD1(set_rate_attitude_euler, Telemetry::Result(double)){};
MOCK_METHOD1(set_rate_camera_attitude, Telemetry::Result(double)){};
MOCK_METHOD1(set_rate_velocity_ned, Telemetry::Result(double)){};
MOCK_METHOD1(set_rate_gps_info, Telemetry::Result(double)){};
MOCK_METHOD1(set_rate_raw_gps, Telemetry::Result(double)){};
Expand Down Expand Up @@ -153,7 +143,6 @@ class MockTelemetry {
MOCK_CONST_METHOD2(
set_rate_attitude_quaternion_async, void(double, Telemetry::ResultCallback)){};
MOCK_CONST_METHOD2(set_rate_attitude_euler_async, void(double, Telemetry::ResultCallback)){};
MOCK_CONST_METHOD2(set_rate_camera_attitude_async, void(double, Telemetry::ResultCallback)){};
MOCK_CONST_METHOD2(set_rate_velocity_ned_async, void(double, Telemetry::ResultCallback)){};
MOCK_CONST_METHOD2(set_rate_gps_info_async, void(double, Telemetry::ResultCallback)){};
MOCK_CONST_METHOD2(set_rate_battery_async, void(double, Telemetry::ResultCallback)){};
Expand Down
42 changes: 0 additions & 42 deletions src/mavsdk/plugins/telemetry/telemetry.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -188,38 +188,6 @@ Telemetry::AngularVelocityBody Telemetry::attitude_angular_velocity_body() const
return _impl->attitude_angular_velocity_body();
}

Telemetry::CameraAttitudeQuaternionHandle
Telemetry::subscribe_camera_attitude_quaternion(const CameraAttitudeQuaternionCallback& callback)
{
return _impl->subscribe_camera_attitude_quaternion(callback);
}

void Telemetry::unsubscribe_camera_attitude_quaternion(CameraAttitudeQuaternionHandle handle)
{
_impl->unsubscribe_camera_attitude_quaternion(handle);
}

Telemetry::Quaternion Telemetry::camera_attitude_quaternion() const
{
return _impl->camera_attitude_quaternion();
}

Telemetry::CameraAttitudeEulerHandle
Telemetry::subscribe_camera_attitude_euler(const CameraAttitudeEulerCallback& callback)
{
return _impl->subscribe_camera_attitude_euler(callback);
}

void Telemetry::unsubscribe_camera_attitude_euler(CameraAttitudeEulerHandle handle)
{
_impl->unsubscribe_camera_attitude_euler(handle);
}

Telemetry::EulerAngle Telemetry::camera_attitude_euler() const
{
return _impl->camera_attitude_euler();
}

Telemetry::VelocityNedHandle Telemetry::subscribe_velocity_ned(const VelocityNedCallback& callback)
{
return _impl->subscribe_velocity_ned(callback);
Expand Down Expand Up @@ -642,16 +610,6 @@ Telemetry::Result Telemetry::set_rate_attitude_euler(double rate_hz) const
return _impl->set_rate_attitude_euler(rate_hz);
}

void Telemetry::set_rate_camera_attitude_async(double rate_hz, const ResultCallback callback)
{
_impl->set_rate_camera_attitude_async(rate_hz, callback);
}

Telemetry::Result Telemetry::set_rate_camera_attitude(double rate_hz) const
{
return _impl->set_rate_camera_attitude(rate_hz);
}

void Telemetry::set_rate_velocity_ned_async(double rate_hz, const ResultCallback callback)
{
_impl->set_rate_velocity_ned_async(rate_hz, callback);
Expand Down
Loading

0 comments on commit e64553a

Please sign in to comment.