Skip to content

Commit 9b6740e

Browse files
committed
core: fixup API naming and docs
This should make the raw connection a bit clearer.
1 parent 250ccb0 commit 9b6740e

File tree

6 files changed

+71
-67
lines changed

6 files changed

+71
-67
lines changed

docs/en/cpp/api_reference/classmavsdk_1_1_mavsdk.md

Lines changed: 21 additions & 21 deletions
Original file line numberDiff line numberDiff line change
@@ -66,9 +66,9 @@ void | [unsubscribe_incoming_messages_json](#classmavsdk_1_1_mavsdk_1a4be244c389
6666
void | [unsubscribe_outgoing_messages_json](#classmavsdk_1_1_mavsdk_1aa3a490358db87cfed617cdad902bb753) ([InterceptJsonHandle](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1a3b40ae4fd8af4c4419b61f0ad955812f) handle) | Unsubscribe from outgoing messages as JSON.
6767
void | [intercept_incoming_messages_async](#classmavsdk_1_1_mavsdk_1ac80c8909958533131cbdbc61d061794f) (std::function< bool(mavlink_message_t &)> callback) | Intercept incoming messages.
6868
void | [intercept_outgoing_messages_async](#classmavsdk_1_1_mavsdk_1a040ee5c1d41e71c0d63cf8f76d2db275) (std::function< bool(mavlink_message_t &)> callback) | Intercept outgoing messages.
69-
bool | [send_raw_bytes](#classmavsdk_1_1_mavsdk_1a59d76dd05fc7dacc949a607d16cf3221) (const char * bytes, size_t length) | Send raw MAVLink bytes.
70-
[RawBytesHandle](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1ac766258f137aa3e8b0dabb5a66435ea1) | [subscribe_raw_bytes](#classmavsdk_1_1_mavsdk_1a377715955e2fd52c1caa960ebe208a57) ([RawBytesCallback](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1acb5be9a1be97d251387ffe87ae8b9eb0) callback) | Subscribe to all outgoing raw bytes.
71-
void | [unsubscribe_raw_bytes](#classmavsdk_1_1_mavsdk_1a19f57749bf10aca6512ad2cbe07c33ab) ([RawBytesHandle](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1ac766258f137aa3e8b0dabb5a66435ea1) handle) | Unsubscribe from raw bytes.
69+
void | [pass_received_raw_bytes](#classmavsdk_1_1_mavsdk_1a65329315ac07bae110839d9e054fbc05) (const char * bytes, size_t length) | Pass received raw MAVLink bytes.
70+
[RawBytesHandle](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1ac766258f137aa3e8b0dabb5a66435ea1) | [subscribe_raw_bytes_to_be_sent](#classmavsdk_1_1_mavsdk_1a116e9bab0efdf7ec90866107ef517b20) ([RawBytesCallback](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1acb5be9a1be97d251387ffe87ae8b9eb0) callback) | Subscribe to raw bytes to be sent.
71+
void | [unsubscribe_raw_bytes_to_be_sent](#classmavsdk_1_1_mavsdk_1af6ec813a9728f4258056fa1f5d399eb1) ([RawBytesHandle](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1ac766258f137aa3e8b0dabb5a66435ea1) handle) | Unsubscribe from raw bytes to be sent.
7272

7373

7474
## Constructor & Destructor Documentation
@@ -611,45 +611,45 @@ This functionality is provided primarily for testing in order to simulate packet
611611

612612
* std::function< bool(mavlink_message_t &)> **callback** - Callback to be called for each outgoing message. To drop a message, return 'false' from the callback.
613613

614-
### send_raw_bytes() {#classmavsdk_1_1_mavsdk_1a59d76dd05fc7dacc949a607d16cf3221}
614+
### pass_received_raw_bytes() {#classmavsdk_1_1_mavsdk_1a65329315ac07bae110839d9e054fbc05}
615615
```cpp
616-
bool mavsdk::Mavsdk::send_raw_bytes(const char *bytes, size_t length)
616+
void mavsdk::Mavsdk::pass_received_raw_bytes(const char *bytes, size_t length)
617617
```
618618
619619
620-
Send raw MAVLink bytes.
620+
Pass received raw MAVLink bytes.
621621
622-
This allows sending raw MAVLink message bytes through all connections. The bytes can contain one or more MAVLink messages.
622+
This allows passing raw MAVLink message bytes into MAVSDK to be processel. The bytes can contain one or more MAVLink messages.
623623
624624
625625
::: info
626-
When this API is first used, heartbeats will be automatically enabled.
626+
Before using this, run add_any_connection("raw://")
627627
:::
628628
629+
This goes together with subscribe_to_bytes_to_send.
630+
629631
**Parameters**
630632
631633
* const char\* **bytes** - Pointer to raw MAVLink message bytes.
632634
* size_t **length** - Number of bytes to send.
633635
634-
**Returns**
635-
636-
&emsp;bool - true if bytes were successfully sent, false otherwise.
637-
638-
### subscribe_raw_bytes() {#classmavsdk_1_1_mavsdk_1a377715955e2fd52c1caa960ebe208a57}
636+
### subscribe_raw_bytes_to_be_sent() {#classmavsdk_1_1_mavsdk_1a116e9bab0efdf7ec90866107ef517b20}
639637
```cpp
640-
RawBytesHandle mavsdk::Mavsdk::subscribe_raw_bytes(RawBytesCallback callback)
638+
RawBytesHandle mavsdk::Mavsdk::subscribe_raw_bytes_to_be_sent(RawBytesCallback callback)
641639
```
642640

643641

644-
Subscribe to all outgoing raw bytes.
642+
Subscribe to raw bytes to be sent.
645643

646-
This allows monitoring all MAVLink bytes that are sent out through any connection. The callback will be called with raw bytes after they are successfully sent.
644+
This allows getting MAVLink bytes that need to be sent out.
647645

648646

649647
::: info
650-
When this API is first used, heartbeats will be automatically enabled.
648+
Before using this, run add_any_connection("raw://")
651649
:::
652650

651+
This goes together with pass_received_raw_bytes. The bytes contain one mavlink message at a time.
652+
653653
**Parameters**
654654

655655
* [RawBytesCallback](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1acb5be9a1be97d251387ffe87ae8b9eb0) **callback** - Callback to be called with outgoing raw bytes.
@@ -658,15 +658,15 @@ When this API is first used, heartbeats will be automatically enabled.
658658

659659
&emsp;[RawBytesHandle](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1ac766258f137aa3e8b0dabb5a66435ea1) - [Handle](classmavsdk_1_1_handle.md) to unsubscribe again.
660660

661-
### unsubscribe_raw_bytes() {#classmavsdk_1_1_mavsdk_1a19f57749bf10aca6512ad2cbe07c33ab}
661+
### unsubscribe_raw_bytes_to_be_sent() {#classmavsdk_1_1_mavsdk_1af6ec813a9728f4258056fa1f5d399eb1}
662662
```cpp
663-
void mavsdk::Mavsdk::unsubscribe_raw_bytes(RawBytesHandle handle)
663+
void mavsdk::Mavsdk::unsubscribe_raw_bytes_to_be_sent(RawBytesHandle handle)
664664
```
665665
666666
667-
Unsubscribe from raw bytes.
667+
Unsubscribe from raw bytes to be sent.
668668
669669
670670
**Parameters**
671671
672-
* [RawBytesHandle](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1ac766258f137aa3e8b0dabb5a66435ea1) **handle** - [Handle](classmavsdk_1_1_handle.md) from subscribe_raw_bytes.
672+
* [RawBytesHandle](classmavsdk_1_1_mavsdk.md#classmavsdk_1_1_mavsdk_1ac766258f137aa3e8b0dabb5a66435ea1) **handle** - [Handle](classmavsdk_1_1_handle.md) from subscribe_raw_bytes_to_be_sent.

src/mavsdk/core/include/mavsdk/mavsdk.h

Lines changed: 16 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -474,38 +474,41 @@ class Mavsdk {
474474
using RawBytesHandle = Handle<const char*, size_t>;
475475

476476
/**
477-
* @brief Send raw MAVLink bytes.
477+
* @brief Pass received raw MAVLink bytes.
478478
*
479-
* This allows sending raw MAVLink message bytes through all connections.
479+
* This allows passing raw MAVLink message bytes into MAVSDK to be processel.
480480
* The bytes can contain one or more MAVLink messages.
481481
*
482-
* @note When this API is first used, heartbeats will be automatically enabled.
482+
* @note Before using this, run add_any_connection("raw://")
483+
*
484+
* This goes together with subscribe_to_bytes_to_send.
483485
*
484486
* @param bytes Pointer to raw MAVLink message bytes.
485487
* @param length Number of bytes to send.
486-
* @return true if bytes were successfully sent, false otherwise.
487488
*/
488-
bool send_raw_bytes(const char* bytes, size_t length);
489+
void pass_received_raw_bytes(const char* bytes, size_t length);
489490

490491
/**
491-
* @brief Subscribe to all outgoing raw bytes.
492+
* @brief Subscribe to raw bytes to be sent.
493+
*
494+
* This allows getting MAVLink bytes that need to be sent out.
492495
*
493-
* This allows monitoring all MAVLink bytes that are sent out through any connection.
494-
* The callback will be called with raw bytes after they are successfully sent.
496+
* @note Before using this, run add_any_connection("raw://")
495497
*
496-
* @note When this API is first used, heartbeats will be automatically enabled.
498+
* This goes together with pass_received_raw_bytes.
499+
* The bytes contain one mavlink message at a time.
497500
*
498501
* @param callback Callback to be called with outgoing raw bytes.
499502
* @return Handle to unsubscribe again.
500503
*/
501-
RawBytesHandle subscribe_raw_bytes(RawBytesCallback callback);
504+
RawBytesHandle subscribe_raw_bytes_to_be_sent(RawBytesCallback callback);
502505

503506
/**
504-
* @brief Unsubscribe from raw bytes.
507+
* @brief Unsubscribe from raw bytes to be sent.
505508
*
506-
* @param handle Handle from subscribe_raw_bytes.
509+
* @param handle Handle from subscribe_raw_bytes_to_be_sent.
507510
*/
508-
void unsubscribe_raw_bytes(RawBytesHandle handle);
511+
void unsubscribe_raw_bytes_to_be_sent(RawBytesHandle handle);
509512

510513
private:
511514
static constexpr int DEFAULT_SYSTEM_ID_AUTOPILOT = 1;

src/mavsdk/core/mavsdk.cpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -234,19 +234,19 @@ void Mavsdk::intercept_outgoing_messages_async(std::function<bool(mavlink_messag
234234
_impl->intercept_outgoing_messages_async(callback);
235235
}
236236

237-
bool Mavsdk::send_raw_bytes(const char* bytes, size_t length)
237+
void Mavsdk::pass_received_raw_bytes(const char* bytes, size_t length)
238238
{
239-
return _impl->send_raw_bytes(bytes, length);
239+
_impl->pass_received_raw_bytes(bytes, length);
240240
}
241241

242-
Mavsdk::RawBytesHandle Mavsdk::subscribe_raw_bytes(RawBytesCallback callback)
242+
Mavsdk::RawBytesHandle Mavsdk::subscribe_raw_bytes_to_be_sent(RawBytesCallback callback)
243243
{
244-
return _impl->subscribe_raw_bytes(callback);
244+
return _impl->subscribe_raw_bytes_to_be_sent(callback);
245245
}
246246

247-
void Mavsdk::unsubscribe_raw_bytes(RawBytesHandle handle)
247+
void Mavsdk::unsubscribe_raw_bytes_to_be_sent(RawBytesHandle handle)
248248
{
249-
_impl->unsubscribe_raw_bytes(handle);
249+
_impl->unsubscribe_raw_bytes_to_be_sent(handle);
250250
}
251251

252252
Mavsdk::ConnectionErrorHandle

src/mavsdk/core/mavsdk_impl.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -1373,20 +1373,20 @@ RawConnection* MavsdkImpl::find_raw_connection()
13731373
return nullptr;
13741374
}
13751375

1376-
bool MavsdkImpl::send_raw_bytes(const char* bytes, size_t length)
1376+
void MavsdkImpl::pass_received_raw_bytes(const char* bytes, size_t length)
13771377
{
13781378
auto* raw_conn = find_raw_connection();
13791379
if (raw_conn == nullptr) {
13801380
LogErr()
13811381
<< "No raw connection available. Please add one using add_any_connection(\"raw://\")";
1382-
return false;
1382+
return;
13831383
}
13841384

13851385
raw_conn->receive(bytes, length);
1386-
return true;
13871386
}
13881387

1389-
Mavsdk::RawBytesHandle MavsdkImpl::subscribe_raw_bytes(const Mavsdk::RawBytesCallback& callback)
1388+
Mavsdk::RawBytesHandle
1389+
MavsdkImpl::subscribe_raw_bytes_to_be_sent(const Mavsdk::RawBytesCallback& callback)
13901390
{
13911391
if (find_raw_connection() == nullptr) {
13921392
LogWarn() << "No raw connection available. Subscription will only receive bytes after you "
@@ -1395,7 +1395,7 @@ Mavsdk::RawBytesHandle MavsdkImpl::subscribe_raw_bytes(const Mavsdk::RawBytesCal
13951395
return _raw_bytes_subscriptions.subscribe(callback);
13961396
}
13971397

1398-
void MavsdkImpl::unsubscribe_raw_bytes(Mavsdk::RawBytesHandle handle)
1398+
void MavsdkImpl::unsubscribe_raw_bytes_to_be_sent(Mavsdk::RawBytesHandle handle)
13991399
{
14001400
_raw_bytes_subscriptions.unsubscribe(handle);
14011401
}

src/mavsdk/core/mavsdk_impl.h

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -103,9 +103,9 @@ class MavsdkImpl {
103103
void unsubscribe_connection_errors(Mavsdk::ConnectionErrorHandle handle);
104104

105105
// Raw bytes API
106-
bool send_raw_bytes(const char* bytes, size_t length);
107-
Mavsdk::RawBytesHandle subscribe_raw_bytes(const Mavsdk::RawBytesCallback& callback);
108-
void unsubscribe_raw_bytes(Mavsdk::RawBytesHandle handle);
106+
void pass_received_raw_bytes(const char* bytes, size_t length);
107+
Mavsdk::RawBytesHandle subscribe_raw_bytes_to_be_sent(const Mavsdk::RawBytesCallback& callback);
108+
void unsubscribe_raw_bytes_to_be_sent(Mavsdk::RawBytesHandle handle);
109109
bool notify_raw_bytes_sent(const char* bytes, size_t length);
110110

111111
std::shared_ptr<ServerComponent> server_component(unsigned instance = 0);

src/system_tests/raw_bytes.cpp

Lines changed: 20 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -23,28 +23,29 @@ TEST(SystemTest, RawBytesHeartbeat)
2323
bool heartbeat_received = false;
2424

2525
// Subscribe to raw bytes to capture the heartbeat response
26-
auto handle = mavsdk_responder.subscribe_raw_bytes([&prom, &heartbeat_received](
27-
const char* bytes, size_t length) {
28-
LogInfo() << "Received " << length << " raw bytes";
26+
auto handle = mavsdk_responder.subscribe_raw_bytes_to_be_sent(
27+
[&prom, &heartbeat_received](const char* bytes, size_t length) {
28+
LogInfo() << "Received " << length << " raw bytes";
2929

30-
// Parse to check if this is a heartbeat
31-
mavlink_message_t msg = {};
32-
mavlink_status_t status = {};
30+
// Parse to check if this is a heartbeat
31+
mavlink_message_t msg = {};
32+
mavlink_status_t status = {};
3333

34-
for (size_t i = 0; i < length; ++i) {
35-
if (mavlink_parse_char(MAVLINK_COMM_0, static_cast<uint8_t>(bytes[i]), &msg, &status)) {
36-
if (msg.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
37-
LogInfo() << "Captured HEARTBEAT message from system " << (int)msg.sysid
38-
<< ", component " << (int)msg.compid;
39-
if (!heartbeat_received) {
40-
heartbeat_received = true;
41-
prom.set_value();
34+
for (size_t i = 0; i < length; ++i) {
35+
if (mavlink_parse_char(
36+
MAVLINK_COMM_0, static_cast<uint8_t>(bytes[i]), &msg, &status)) {
37+
if (msg.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
38+
LogInfo() << "Captured HEARTBEAT message from system " << (int)msg.sysid
39+
<< ", component " << (int)msg.compid;
40+
if (!heartbeat_received) {
41+
heartbeat_received = true;
42+
prom.set_value();
43+
}
44+
return;
4245
}
43-
return;
4446
}
4547
}
46-
}
47-
});
48+
});
4849

4950
// Give subscription time to be registered
5051
std::this_thread::sleep_for(std::chrono::milliseconds(100));
@@ -71,7 +72,7 @@ TEST(SystemTest, RawBytesHeartbeat)
7172
std::thread heartbeat_thread([&]() {
7273
while (should_send_heartbeats) {
7374
LogInfo() << "Sending raw heartbeat (" << len << " bytes)...";
74-
mavsdk_responder.send_raw_bytes(
75+
mavsdk_responder.pass_received_raw_bytes(
7576
reinterpret_cast<const char*>(heartbeat_bytes.data()), len);
7677
std::this_thread::sleep_for(std::chrono::seconds(1));
7778
}
@@ -87,5 +88,5 @@ TEST(SystemTest, RawBytesHeartbeat)
8788
should_send_heartbeats = false;
8889
heartbeat_thread.join();
8990

90-
mavsdk_responder.unsubscribe_raw_bytes(handle);
91+
mavsdk_responder.unsubscribe_raw_bytes_to_be_sent(handle);
9192
}

0 commit comments

Comments
 (0)