Porting mros2 as an Mbed library.
Dependents: mbed-os-example-mros2 example-mbed-mros2-sub-pose example-mbed-mros2-pub-twist example-mbed-mros2-mturtle-teleop
embeddedRTPS/include/rtps/config_stm.h@7:c80f65422d99, 2022-03-19 (annotated)
- Committer:
- smoritaemb
- Date:
- Sat Mar 19 09:23:37 2022 +0900
- Revision:
- 7:c80f65422d99
- Parent:
- 0:580aba13d1a1
Merge test_assortment_of_msgs branch.
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
smoritaemb | 0:580aba13d1a1 | 1 | /* |
smoritaemb | 0:580aba13d1a1 | 2 | The MIT License |
smoritaemb | 0:580aba13d1a1 | 3 | Copyright (c) 2019 Lehrstuhl Informatik 11 - RWTH Aachen University |
smoritaemb | 0:580aba13d1a1 | 4 | Permission is hereby granted, free of charge, to any person obtaining a copy |
smoritaemb | 0:580aba13d1a1 | 5 | of this software and associated documentation files (the "Software"), to deal |
smoritaemb | 0:580aba13d1a1 | 6 | in the Software without restriction, including without limitation the rights |
smoritaemb | 0:580aba13d1a1 | 7 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell |
smoritaemb | 0:580aba13d1a1 | 8 | copies of the Software, and to permit persons to whom the Software is |
smoritaemb | 0:580aba13d1a1 | 9 | furnished to do so, subject to the following conditions: |
smoritaemb | 0:580aba13d1a1 | 10 | The above copyright notice and this permission notice shall be included in |
smoritaemb | 0:580aba13d1a1 | 11 | all copies or substantial portions of the Software. |
smoritaemb | 0:580aba13d1a1 | 12 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR |
smoritaemb | 0:580aba13d1a1 | 13 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, |
smoritaemb | 0:580aba13d1a1 | 14 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE |
smoritaemb | 0:580aba13d1a1 | 15 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER |
smoritaemb | 0:580aba13d1a1 | 16 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, |
smoritaemb | 0:580aba13d1a1 | 17 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN |
smoritaemb | 0:580aba13d1a1 | 18 | THE SOFTWARE |
smoritaemb | 0:580aba13d1a1 | 19 | |
smoritaemb | 0:580aba13d1a1 | 20 | This file is part of embeddedRTPS. |
smoritaemb | 0:580aba13d1a1 | 21 | |
smoritaemb | 0:580aba13d1a1 | 22 | Author: i11 - Embedded Software, RWTH Aachen University |
smoritaemb | 0:580aba13d1a1 | 23 | */ |
smoritaemb | 0:580aba13d1a1 | 24 | |
smoritaemb | 0:580aba13d1a1 | 25 | #ifndef RTPS_CONFIG_H |
smoritaemb | 0:580aba13d1a1 | 26 | #define RTPS_CONFIG_H |
smoritaemb | 0:580aba13d1a1 | 27 | |
smoritaemb | 0:580aba13d1a1 | 28 | #include "rtps/common/types.h" |
smoritaemb | 0:580aba13d1a1 | 29 | |
smoritaemb | 0:580aba13d1a1 | 30 | namespace rtps { |
smoritaemb | 0:580aba13d1a1 | 31 | |
smoritaemb | 0:580aba13d1a1 | 32 | #define IS_LITTLE_ENDIAN 1 |
smoritaemb | 0:580aba13d1a1 | 33 | |
smoritaemb | 0:580aba13d1a1 | 34 | namespace Config { |
smoritaemb | 0:580aba13d1a1 | 35 | const VendorId_t VENDOR_ID = {13, 37}; |
smoritaemb | 0:580aba13d1a1 | 36 | const std::array<uint8_t, 4> IP_ADDRESS = { |
smoritaemb | 0:580aba13d1a1 | 37 | 192, 168, 0, 47}; // Needs to be set in lwipcfg.h too. |
smoritaemb | 0:580aba13d1a1 | 38 | const GuidPrefix_t BASE_GUID_PREFIX{1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 12}; |
smoritaemb | 0:580aba13d1a1 | 39 | |
smoritaemb | 0:580aba13d1a1 | 40 | const uint8_t DOMAIN_ID = 0; // 230 possible with UDP |
smoritaemb | 0:580aba13d1a1 | 41 | const uint8_t NUM_STATELESS_WRITERS = 2; |
smoritaemb | 0:580aba13d1a1 | 42 | const uint8_t NUM_STATELESS_READERS = 2; |
smoritaemb | 0:580aba13d1a1 | 43 | const uint8_t NUM_STATEFUL_READERS = 2; |
smoritaemb | 0:580aba13d1a1 | 44 | const uint8_t NUM_STATEFUL_WRITERS = 2; |
smoritaemb | 0:580aba13d1a1 | 45 | const uint8_t MAX_NUM_PARTICIPANTS = 1; |
smoritaemb | 0:580aba13d1a1 | 46 | const uint8_t NUM_WRITERS_PER_PARTICIPANT = 4; |
smoritaemb | 0:580aba13d1a1 | 47 | const uint8_t NUM_READERS_PER_PARTICIPANT = 4; |
smoritaemb | 0:580aba13d1a1 | 48 | const uint8_t NUM_WRITER_PROXIES_PER_READER = 3; |
smoritaemb | 0:580aba13d1a1 | 49 | const uint8_t NUM_READER_PROXIES_PER_WRITER = 3; |
smoritaemb | 0:580aba13d1a1 | 50 | |
smoritaemb | 0:580aba13d1a1 | 51 | const uint8_t HISTORY_SIZE = 10; |
smoritaemb | 0:580aba13d1a1 | 52 | |
smoritaemb | 0:580aba13d1a1 | 53 | const uint8_t MAX_TYPENAME_LENGTH = 20; |
smoritaemb | 0:580aba13d1a1 | 54 | const uint8_t MAX_TOPICNAME_LENGTH = 20; |
smoritaemb | 0:580aba13d1a1 | 55 | |
smoritaemb | 0:580aba13d1a1 | 56 | const int HEARTBEAT_STACKSIZE = 1200; // byte |
smoritaemb | 0:580aba13d1a1 | 57 | const int THREAD_POOL_WRITER_STACKSIZE = 1100; // byte |
smoritaemb | 0:580aba13d1a1 | 58 | const int THREAD_POOL_READER_STACKSIZE = 1600; // byte |
smoritaemb | 0:580aba13d1a1 | 59 | const uint16_t SPDP_WRITER_STACKSIZE = 550; // byte |
smoritaemb | 0:580aba13d1a1 | 60 | |
smoritaemb | 0:580aba13d1a1 | 61 | const uint16_t SF_WRITER_HB_PERIOD_MS = 4000; |
smoritaemb | 0:580aba13d1a1 | 62 | const uint16_t SPDP_RESEND_PERIOD_MS = 10000; |
smoritaemb | 0:580aba13d1a1 | 63 | const uint8_t SPDP_WRITER_PRIO = 3; |
smoritaemb | 0:580aba13d1a1 | 64 | const uint8_t SPDP_MAX_NUMBER_FOUND_PARTICIPANTS = 5; |
smoritaemb | 0:580aba13d1a1 | 65 | const uint8_t SPDP_MAX_NUM_LOCATORS = 5; |
smoritaemb | 0:580aba13d1a1 | 66 | const Duration_t SPDP_LEASE_DURATION = {100, 0}; |
smoritaemb | 0:580aba13d1a1 | 67 | |
smoritaemb | 0:580aba13d1a1 | 68 | const int MAX_NUM_UDP_CONNECTIONS = 10; |
smoritaemb | 0:580aba13d1a1 | 69 | |
smoritaemb | 0:580aba13d1a1 | 70 | const int THREAD_POOL_NUM_WRITERS = 1; |
smoritaemb | 0:580aba13d1a1 | 71 | const int THREAD_POOL_NUM_READERS = 1; |
smoritaemb | 0:580aba13d1a1 | 72 | const int THREAD_POOL_WRITER_PRIO = 3; |
smoritaemb | 0:580aba13d1a1 | 73 | const int THREAD_POOL_READER_PRIO = 3; |
smoritaemb | 0:580aba13d1a1 | 74 | const int THREAD_POOL_WORKLOAD_QUEUE_LENGTH = 10; |
smoritaemb | 0:580aba13d1a1 | 75 | |
smoritaemb | 0:580aba13d1a1 | 76 | constexpr int OVERALL_HEAP_SIZE = |
smoritaemb | 0:580aba13d1a1 | 77 | THREAD_POOL_NUM_WRITERS * THREAD_POOL_WRITER_STACKSIZE + |
smoritaemb | 0:580aba13d1a1 | 78 | THREAD_POOL_NUM_READERS * THREAD_POOL_READER_STACKSIZE + |
smoritaemb | 0:580aba13d1a1 | 79 | MAX_NUM_PARTICIPANTS * SPDP_WRITER_STACKSIZE + |
smoritaemb | 0:580aba13d1a1 | 80 | NUM_STATEFUL_WRITERS * HEARTBEAT_STACKSIZE; |
smoritaemb | 0:580aba13d1a1 | 81 | } // namespace Config |
smoritaemb | 0:580aba13d1a1 | 82 | } // namespace rtps |
smoritaemb | 0:580aba13d1a1 | 83 | |
smoritaemb | 0:580aba13d1a1 | 84 | #endif // RTPS_CONFIG_H |