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

telemetry: split attitude into Euler + Quaternion #1878

Merged
merged 1 commit into from
Sep 6, 2022
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
2 changes: 1 addition & 1 deletion proto
6 changes: 5 additions & 1 deletion src/integration_tests/telemetry_async.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,11 @@ TEST_F(SitlTest, PX4TelemetryAsync)
10.0, [](Telemetry::Result result) { return receive_result(result); });
std::this_thread::sleep_for(std::chrono::milliseconds(100));

telemetry->set_rate_attitude_async(
telemetry->set_rate_attitude_euler_async(
10.0, [](Telemetry::Result result) { return receive_result(result); });
std::this_thread::sleep_for(std::chrono::milliseconds(100));

telemetry->set_rate_attitude_quaternion_async(
10.0, [](Telemetry::Result result) { return receive_result(result); });
std::this_thread::sleep_for(std::chrono::milliseconds(100));

Expand Down
3 changes: 2 additions & 1 deletion src/integration_tests/telemetry_sync.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,8 @@ TEST_F(SitlTest, PX4TelemetrySync)
EXPECT_EQ(telemetry->set_rate_position(10.0), Telemetry::Result::Success);
EXPECT_EQ(telemetry->set_rate_home(10.0), Telemetry::Result::Success);
EXPECT_EQ(telemetry->set_rate_in_air(10.0), Telemetry::Result::Success);
EXPECT_EQ(telemetry->set_rate_attitude(10.0), Telemetry::Result::Success);
EXPECT_EQ(telemetry->set_rate_attitude_quaternion(10.0), Telemetry::Result::Success);
EXPECT_EQ(telemetry->set_rate_attitude_euler(10.0), Telemetry::Result::Success);
EXPECT_EQ(telemetry->set_rate_velocity_ned(10.0), Telemetry::Result::Success);
EXPECT_EQ(telemetry->set_rate_gps_info(10.0), Telemetry::Result::Success);
EXPECT_EQ(telemetry->set_rate_battery(10.0), Telemetry::Result::Success);
Expand Down
31 changes: 25 additions & 6 deletions src/mavsdk/plugins/telemetry/include/plugins/telemetry/telemetry.h
Original file line number Diff line number Diff line change
Expand Up @@ -1963,20 +1963,39 @@ class Telemetry : public PluginBase {
Result set_rate_vtol_state(double rate_hz) const;

/**
* @brief Set rate to 'attitude' updates.
* @brief Set rate to 'attitude euler angle' updates.
*
* This function is non-blocking. See 'set_rate_attitude' for the blocking counterpart.
* This function is non-blocking. See 'set_rate_attitude_quaternion' for the blocking
* counterpart.
*/
void set_rate_attitude_async(double rate_hz, const ResultCallback callback);
void set_rate_attitude_quaternion_async(double rate_hz, const ResultCallback callback);

/**
* @brief Set rate to 'attitude' updates.
* @brief Set rate to 'attitude euler angle' updates.
*
* This function is blocking. See 'set_rate_attitude_quaternion_async' for the non-blocking
* counterpart.
*
* This function is blocking. See 'set_rate_attitude_async' for the non-blocking counterpart.
* @return Result of request.
*/
Result set_rate_attitude_quaternion(double rate_hz) const;

/**
* @brief Set rate to 'attitude quaternion' updates.
*
* This function is non-blocking. See 'set_rate_attitude_euler' for the blocking counterpart.
*/
void set_rate_attitude_euler_async(double rate_hz, const ResultCallback callback);

/**
* @brief Set rate to 'attitude quaternion' updates.
*
* This function is blocking. See 'set_rate_attitude_euler_async' for the non-blocking
* counterpart.
*
* @return Result of request.
*/
Result set_rate_attitude(double rate_hz) const;
Result set_rate_attitude_euler(double rate_hz) const;

/**
* @brief Set rate of camera attitude updates.
Expand Down
7 changes: 5 additions & 2 deletions src/mavsdk/plugins/telemetry/mocks/telemetry_mock.h
Original file line number Diff line number Diff line change
Expand Up @@ -121,7 +121,8 @@ class MockTelemetry {
MOCK_METHOD1(set_rate_home, Telemetry::Result(double)){};
MOCK_METHOD1(set_rate_in_air, Telemetry::Result(double)){};
MOCK_METHOD1(set_rate_landed_state, Telemetry::Result(double)){};
MOCK_METHOD1(set_rate_attitude, 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)){};
Expand All @@ -146,7 +147,9 @@ class MockTelemetry {
MOCK_CONST_METHOD2(set_rate_home_async, void(double, Telemetry::ResultCallback)){};
MOCK_CONST_METHOD2(set_rate_in_air_async, void(double, Telemetry::ResultCallback)){};
MOCK_CONST_METHOD2(set_rate_landed_state_async, void(double, Telemetry::ResultCallback)){};
MOCK_CONST_METHOD2(set_rate_attitude_async, void(double, Telemetry::ResultCallback)){};
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)){};
Expand Down
18 changes: 14 additions & 4 deletions src/mavsdk/plugins/telemetry/telemetry.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -606,14 +606,24 @@ Telemetry::Result Telemetry::set_rate_vtol_state(double rate_hz) const
return _impl->set_rate_vtol_state(rate_hz);
}

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

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

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

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)
Expand Down
32 changes: 20 additions & 12 deletions src/mavsdk/plugins/telemetry/telemetry_impl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -283,12 +283,18 @@ Telemetry::Result TelemetryImpl::set_rate_landed_state(double rate_hz)
_parent->set_msg_rate(MAVLINK_MSG_ID_EXTENDED_SYS_STATE, rate_hz));
}

Telemetry::Result TelemetryImpl::set_rate_attitude(double rate_hz)
Telemetry::Result TelemetryImpl::set_rate_attitude_quaternion(double rate_hz)
{
return telemetry_result_from_command_result(
_parent->set_msg_rate(MAVLINK_MSG_ID_ATTITUDE_QUATERNION, rate_hz));
}

Telemetry::Result TelemetryImpl::set_rate_attitude_euler(double rate_hz)
{
return telemetry_result_from_command_result(
_parent->set_msg_rate(MAVLINK_MSG_ID_ATTITUDE, rate_hz));
}

Telemetry::Result TelemetryImpl::set_rate_camera_attitude(double rate_hz)
{
return telemetry_result_from_command_result(
Expand Down Expand Up @@ -443,7 +449,8 @@ void TelemetryImpl::set_rate_landed_state_async(double rate_hz, Telemetry::Resul
});
}

void TelemetryImpl::set_rate_attitude_async(double rate_hz, Telemetry::ResultCallback callback)
void TelemetryImpl::set_rate_attitude_quaternion_async(
double rate_hz, Telemetry::ResultCallback callback)
{
_parent->set_msg_rate_async(
MAVLINK_MSG_ID_ATTITUDE_QUATERNION,
Expand All @@ -453,6 +460,17 @@ void TelemetryImpl::set_rate_attitude_async(double rate_hz, Telemetry::ResultCal
});
}

void TelemetryImpl::set_rate_attitude_euler_async(
double rate_hz, Telemetry::ResultCallback callback)
{
_parent->set_msg_rate_async(
MAVLINK_MSG_ID_ATTITUDE,
rate_hz,
[callback](MavlinkCommandSender::Result command_result, float) {
command_result_callback(command_result, callback);
});
}

void TelemetryImpl::set_rate_camera_attitude_async(
double rate_hz, Telemetry::ResultCallback callback)
{
Expand Down Expand Up @@ -752,13 +770,6 @@ void TelemetryImpl::process_attitude(const mavlink_message_t& message)
angular_velocity_body.yaw_rad_s = attitude.yawspeed;
set_attitude_angular_velocity_body(angular_velocity_body);

auto quaternion = mavsdk::to_quaternion_from_euler_angle(euler_angle);
set_attitude_quaternion(quaternion);

std::lock_guard<std::mutex> lock(_subscription_mutex);
_attitude_quaternion_angle_subscriptions.queue(
attitude_quaternion(), [this](const auto& func) { _parent->call_user_callback(func); });

_attitude_euler_angle_subscriptions.queue(
attitude_euler(), [this](const auto& func) { _parent->call_user_callback(func); });

Expand Down Expand Up @@ -793,9 +804,6 @@ void TelemetryImpl::process_attitude_quaternion(const mavlink_message_t& message
_attitude_quaternion_angle_subscriptions.queue(
attitude_quaternion(), [this](const auto& func) { _parent->call_user_callback(func); });

_attitude_euler_angle_subscriptions.queue(
attitude_euler(), [this](const auto& func) { _parent->call_user_callback(func); });

_attitude_angular_velocity_body_subscriptions.queue(
attitude_angular_velocity_body(),
[this](const auto& func) { _parent->call_user_callback(func); });
Expand Down
6 changes: 4 additions & 2 deletions src/mavsdk/plugins/telemetry/telemetry_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,8 @@ class TelemetryImpl : public PluginImplBase {
Telemetry::Result set_rate_in_air(double rate_hz);
Telemetry::Result set_rate_landed_state(double rate_hz);
Telemetry::Result set_rate_vtol_state(double rate_hz);
Telemetry::Result set_rate_attitude(double rate_hz);
Telemetry::Result set_rate_attitude_quaternion(double rate_hz);
Telemetry::Result set_rate_attitude_euler(double rate_hz);
Telemetry::Result set_rate_camera_attitude(double rate_hz);
Telemetry::Result set_rate_velocity_ned(double rate_hz);
Telemetry::Result set_rate_imu(double rate_hz);
Expand All @@ -56,7 +57,8 @@ class TelemetryImpl : public PluginImplBase {
void set_rate_in_air_async(double rate_hz, Telemetry::ResultCallback callback);
void set_rate_landed_state_async(double rate_hz, Telemetry::ResultCallback callback);
void set_rate_vtol_state_async(double rate_hz, Telemetry::ResultCallback callback);
void set_rate_attitude_async(double rate_hz, Telemetry::ResultCallback callback);
void set_rate_attitude_quaternion_async(double rate_hz, Telemetry::ResultCallback callback);
void set_rate_attitude_euler_async(double rate_hz, Telemetry::ResultCallback callback);
void set_rate_camera_attitude_async(double rate_hz, Telemetry::ResultCallback callback);
void set_rate_velocity_ned_async(double rate_hz, Telemetry::ResultCallback callback);
void set_rate_imu_async(double rate_hz, Telemetry::ResultCallback callback);
Expand Down
Loading