• Home
  • Features
  • Pricing
  • Docs
  • Announcements
  • Sign In

mavlink / MAVSDK / 14459937051

15 Apr 2025 02:29AM UTC coverage: 44.201% (-0.1%) from 44.296%
14459937051

push

github

web-flow
Merge pull request #2538 from Luc-Meunier/vio

mocap: Add vision speed estimate

0 of 63 new or added lines in 2 files covered. (0.0%)

7 existing lines in 2 files now uncovered.

14603 of 33038 relevant lines covered (44.2%)

281.89 hits per line

Source File
Press 'n' to go to next uncovered line, 'b' for previous

0.0
/src/mavsdk/plugins/mocap/mocap_impl.cpp
1
#include "mocap_impl.h"
2
#include "mavlink_address.h"
3
#include "system.h"
4
#include "px4_custom_mode.h"
5
#include <array>
6
#include <ctime>
7

8
namespace mavsdk {
9

10
void MocapImpl::init() {}
×
11

12
void MocapImpl::deinit() {}
×
13

14
void MocapImpl::enable() {}
×
15

16
void MocapImpl::disable() {}
×
17

18
MocapImpl::MocapImpl(System& system) : PluginImplBase(system)
×
19
{
20
    _system_impl->register_plugin(this);
×
21
}
×
22

23
MocapImpl::MocapImpl(std::shared_ptr<System> system) : PluginImplBase(std::move(system))
×
24
{
25
    _system_impl->register_plugin(this);
×
26
}
×
27

28
MocapImpl::~MocapImpl()
×
29
{
30
    _system_impl->unregister_plugin(this);
×
31
}
×
32

33
Mocap::Result MocapImpl::set_vision_position_estimate(
×
34
    const Mocap::VisionPositionEstimate& vision_position_estimate)
35
{
36
    if (!_system_impl->is_connected()) {
×
37
        return Mocap::Result::NoSystem;
×
38
    }
39

40
    return send_vision_position_estimate(vision_position_estimate);
×
41
}
42

43
Mocap::Result
NEW
44
MocapImpl::set_vision_speed_estimate(const Mocap::VisionSpeedEstimate& vision_speed_estimate)
×
45
{
NEW
46
    if (!_system_impl->is_connected()) {
×
NEW
47
        return Mocap::Result::NoSystem;
×
48
    }
49

NEW
50
    return send_vision_speed_estimate(vision_speed_estimate);
×
51
}
52

53
Mocap::Result
54
MocapImpl::set_attitude_position_mocap(const Mocap::AttitudePositionMocap& attitude_position_mocap)
×
55
{
56
    if (!_system_impl->is_connected()) {
×
57
        return Mocap::Result::NoSystem;
×
58
    }
59

60
    return send_attitude_position_mocap(attitude_position_mocap);
×
61
}
62

63
Mocap::Result MocapImpl::set_odometry(const Mocap::Odometry& odometry)
×
64
{
65
    if (!_system_impl->is_connected()) {
×
66
        return Mocap::Result::NoSystem;
×
67
    }
68

69
    return send_odometry(odometry);
×
70
}
71

72
Mocap::Result MocapImpl::send_vision_position_estimate(
×
73
    const Mocap::VisionPositionEstimate& vision_position_estimate)
74
{
75
    const uint64_t autopilot_time_usec =
×
76
        (!vision_position_estimate.time_usec) ?
×
77
            std::chrono::duration_cast<std::chrono::microseconds>(
×
78
                _system_impl->get_autopilot_time().now().time_since_epoch())
×
79
                .count() :
×
80
            std::chrono::duration_cast<std::chrono::microseconds>(
×
81
                _system_impl->get_autopilot_time()
×
82
                    .time_in(SystemTimePoint(
×
83
                        std::chrono::microseconds(vision_position_estimate.time_usec)))
×
84
                    .time_since_epoch())
×
85
                .count();
×
86

87
    std::array<float, 21> covariance{};
×
88

89
    // The covariance matrix needs to have length 21 or 1 with the one entry set to NaN.
90

91
    if (vision_position_estimate.pose_covariance.covariance_matrix.size() == 21) {
×
92
        std::copy(
×
93
            vision_position_estimate.pose_covariance.covariance_matrix.begin(),
94
            vision_position_estimate.pose_covariance.covariance_matrix.end(),
95
            covariance.begin());
96
    } else if (
×
97
        vision_position_estimate.pose_covariance.covariance_matrix.size() == 1 &&
×
98
        std::isnan(vision_position_estimate.pose_covariance.covariance_matrix[0])) {
×
99
        covariance[0] = NAN;
×
100
    } else {
101
        return Mocap::Result::InvalidRequestData;
×
102
    }
103

104
    return _system_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
105
        mavlink_message_t message;
106
        mavlink_msg_vision_position_estimate_pack_chan(
×
107
            mavlink_address.system_id,
×
108
            mavlink_address.component_id,
×
109
            channel,
110
            &message,
111
            autopilot_time_usec,
×
112
            vision_position_estimate.position_body.x_m,
×
113
            vision_position_estimate.position_body.y_m,
×
114
            vision_position_estimate.position_body.z_m,
×
115
            vision_position_estimate.angle_body.roll_rad,
×
116
            vision_position_estimate.angle_body.pitch_rad,
×
117
            vision_position_estimate.angle_body.yaw_rad,
×
118
            covariance.data(),
×
119
            0); // FIXME: reset_counter not set
120
        return message;
×
121
    }) ?
×
122
               Mocap::Result::Success :
123
               Mocap::Result::ConnectionError;
×
124
}
125

126
Mocap::Result
NEW
127
MocapImpl::send_vision_speed_estimate(const Mocap::VisionSpeedEstimate& vision_speed_estimate)
×
128
{
NEW
129
    const uint64_t autopilot_time_usec =
×
NEW
130
        (!vision_speed_estimate.time_usec) ?
×
NEW
131
            std::chrono::duration_cast<std::chrono::microseconds>(
×
NEW
132
                _system_impl->get_autopilot_time().now().time_since_epoch())
×
NEW
133
                .count() :
×
NEW
134
            std::chrono::duration_cast<std::chrono::microseconds>(
×
NEW
135
                _system_impl->get_autopilot_time()
×
NEW
136
                    .time_in(
×
NEW
137
                        SystemTimePoint(std::chrono::microseconds(vision_speed_estimate.time_usec)))
×
NEW
138
                    .time_since_epoch())
×
NEW
139
                .count();
×
140

NEW
141
    std::array<float, 9> covariance{};
×
142

143
    // The covariance matrix needs to have length 9 or 1 with the one entry set to NaN.
144

NEW
145
    if (vision_speed_estimate.speed_covariance.covariance_matrix.size() == 9) {
×
NEW
146
        std::copy(
×
147
            vision_speed_estimate.speed_covariance.covariance_matrix.begin(),
148
            vision_speed_estimate.speed_covariance.covariance_matrix.end(),
149
            covariance.begin());
NEW
150
    } else if (
×
NEW
151
        vision_speed_estimate.speed_covariance.covariance_matrix.size() == 1 &&
×
NEW
152
        std::isnan(vision_speed_estimate.speed_covariance.covariance_matrix[0])) {
×
NEW
153
        covariance[0] = NAN;
×
154
    } else {
NEW
155
        return Mocap::Result::InvalidRequestData;
×
156
    }
157

NEW
158
    return _system_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
159
        mavlink_message_t message;
NEW
160
        mavlink_msg_vision_speed_estimate_pack_chan(
×
NEW
161
            mavlink_address.system_id,
×
NEW
162
            mavlink_address.component_id,
×
163
            channel,
164
            &message,
NEW
165
            autopilot_time_usec,
×
NEW
166
            vision_speed_estimate.speed_ned.north_m_s,
×
NEW
167
            vision_speed_estimate.speed_ned.east_m_s,
×
NEW
168
            vision_speed_estimate.speed_ned.down_m_s,
×
NEW
169
            covariance.data(),
×
170
            0); // FIXME: reset_counter not set
NEW
171
        return message;
×
NEW
172
    }) ?
×
173
               Mocap::Result::Success :
NEW
174
               Mocap::Result::ConnectionError;
×
175
}
176

177
Mocap::Result
178
MocapImpl::send_attitude_position_mocap(const Mocap::AttitudePositionMocap& attitude_position_mocap)
×
179
{
180
    const uint64_t autopilot_time_usec =
×
181
        (!attitude_position_mocap.time_usec) ?
×
182
            std::chrono::duration_cast<std::chrono::microseconds>(
×
183
                _system_impl->get_autopilot_time().now().time_since_epoch())
×
184
                .count() :
×
185
            std::chrono::duration_cast<std::chrono::microseconds>(
×
186
                _system_impl->get_autopilot_time()
×
187
                    .time_in(SystemTimePoint(
×
188
                        std::chrono::microseconds(attitude_position_mocap.time_usec)))
×
189
                    .time_since_epoch())
×
190
                .count();
×
191

192
    mavlink_message_t message;
×
193

194
    std::array<float, 4> q{};
×
195
    q[0] = attitude_position_mocap.q.w;
×
196
    q[1] = attitude_position_mocap.q.x;
×
197
    q[2] = attitude_position_mocap.q.y;
×
198
    q[3] = attitude_position_mocap.q.z;
×
199

200
    std::array<float, 21> covariance{};
×
201

202
    // The covariance matrix needs to have length 21 or 1 with the one entry set to NaN.
203

204
    if (attitude_position_mocap.pose_covariance.covariance_matrix.size() == 21) {
×
205
        std::copy(
×
206
            attitude_position_mocap.pose_covariance.covariance_matrix.begin(),
207
            attitude_position_mocap.pose_covariance.covariance_matrix.end(),
208
            covariance.begin());
209
    } else if (
×
210
        attitude_position_mocap.pose_covariance.covariance_matrix.size() == 1 &&
×
211
        std::isnan(attitude_position_mocap.pose_covariance.covariance_matrix[0])) {
×
212
        covariance[0] = NAN;
×
213
    } else {
214
        return Mocap::Result::InvalidRequestData;
×
215
    }
216

217
    return _system_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
218
        mavlink_msg_att_pos_mocap_pack_chan(
×
219
            mavlink_address.system_id,
×
220
            mavlink_address.component_id,
×
221
            channel,
222
            &message,
×
223
            autopilot_time_usec,
×
224
            q.data(),
×
225
            attitude_position_mocap.position_body.x_m,
×
226
            attitude_position_mocap.position_body.y_m,
×
227
            attitude_position_mocap.position_body.z_m,
×
228
            covariance.data());
×
229
        return message;
×
230
    }) ?
×
231
               Mocap::Result::Success :
232
               Mocap::Result::ConnectionError;
×
233
}
234

235
Mocap::Result MocapImpl::send_odometry(const Mocap::Odometry& odometry)
×
236
{
237
    const uint64_t autopilot_time_usec =
×
238
        (!odometry.time_usec) ?
×
239
            std::chrono::duration_cast<std::chrono::microseconds>(
×
240
                _system_impl->get_autopilot_time().now().time_since_epoch())
×
241
                .count() :
×
242
            std::chrono::duration_cast<std::chrono::microseconds>(
×
243
                _system_impl->get_autopilot_time()
×
244
                    .time_in(SystemTimePoint(std::chrono::microseconds(odometry.time_usec)))
×
245
                    .time_since_epoch())
×
246
                .count();
×
247

248
    std::array<float, 4> q{};
×
249
    q[0] = odometry.q.w;
×
250
    q[1] = odometry.q.x;
×
251
    q[2] = odometry.q.y;
×
252
    q[3] = odometry.q.z;
×
253

254
    std::array<float, 21> pose_covariance{};
×
255
    std::array<float, 21> velocity_covariance{};
×
256

257
    // The covariance matrix needs to have length 21 or 1 with the one entry set to NaN.
258

259
    if (odometry.pose_covariance.covariance_matrix.size() == 21) {
×
260
        std::copy(
×
261
            odometry.pose_covariance.covariance_matrix.begin(),
262
            odometry.pose_covariance.covariance_matrix.end(),
263
            pose_covariance.begin());
264
    } else if (
×
265
        odometry.pose_covariance.covariance_matrix.size() == 1 &&
×
266
        std::isnan(odometry.pose_covariance.covariance_matrix[0])) {
×
267
        pose_covariance[0] = NAN;
×
268
    } else {
269
        return Mocap::Result::InvalidRequestData;
×
270
    }
271

272
    if (odometry.velocity_covariance.covariance_matrix.size() == 21) {
×
273
        std::copy(
×
274
            odometry.velocity_covariance.covariance_matrix.begin(),
275
            odometry.velocity_covariance.covariance_matrix.end(),
276
            velocity_covariance.begin());
277
    } else if (
×
278
        odometry.velocity_covariance.covariance_matrix.size() == 1 &&
×
279
        std::isnan(odometry.velocity_covariance.covariance_matrix[0])) {
×
280
        velocity_covariance[0] = NAN;
×
281
    } else {
282
        return Mocap::Result::InvalidRequestData;
×
283
    }
284

285
    return _system_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
286
        mavlink_message_t message;
287
        mavlink_msg_odometry_pack_chan(
×
288
            mavlink_address.system_id,
×
289
            mavlink_address.component_id,
×
290
            channel,
291
            &message,
292
            autopilot_time_usec,
×
293
            static_cast<uint8_t>(odometry.frame_id),
×
294
            static_cast<uint8_t>(MAV_FRAME_BODY_FRD),
295
            odometry.position_body.x_m,
×
296
            odometry.position_body.y_m,
×
297
            odometry.position_body.z_m,
×
298
            q.data(),
×
299
            odometry.speed_body.x_m_s,
×
300
            odometry.speed_body.y_m_s,
×
301
            odometry.speed_body.z_m_s,
×
302
            odometry.angular_velocity_body.roll_rad_s,
×
303
            odometry.angular_velocity_body.pitch_rad_s,
×
304
            odometry.angular_velocity_body.yaw_rad_s,
×
305
            pose_covariance.data(),
×
306
            velocity_covariance.data(),
×
307
            0,
308
            MAV_ESTIMATOR_TYPE_MOCAP,
309
            0);
310
        return message;
×
311
    }) ?
×
312
               Mocap::Result::Success :
313
               Mocap::Result::ConnectionError;
×
314
}
315

316
} // namespace mavsdk
STATUS · Troubleshooting · Open an Issue · Sales · Support · CAREERS · ENTERPRISE · START FREE · SCHEDULE DEMO
ANNOUNCEMENTS · TWITTER · TOS & SLA · Supported CI Services · What's a CI service? · Automated Testing

© 2025 Coveralls, Inc