From 0d76e8479c81cc4f13ff1ffd3e3ce9fb1e06b050 Mon Sep 17 00:00:00 2001 From: takasehideki Date: Wed, 20 Sep 2023 19:11:25 +0900 Subject: [PATCH] move custom_msgs/ to mros2 repo because it is common feature relate: https://github.com/mROS-base/mros2/pull/51 --- README.md | 64 +--- .../custom_msgs/geometry_msgs/msg/Point.msg | 3 - .../custom_msgs/geometry_msgs/msg/Pose.msg | 2 - .../geometry_msgs/msg/Quaternion.msg | 4 - .../custom_msgs/geometry_msgs/msg/Twist.msg | 2 - .../custom_msgs/geometry_msgs/msg/Vector3.msg | 3 - .../custom_msgs/geometry_msgs/msg/point.hpp | 272 ---------------- .../custom_msgs/geometry_msgs/msg/pose.hpp | 213 ------------ .../geometry_msgs/msg/quaternion.hpp | 307 ------------------ .../custom_msgs/geometry_msgs/msg/twist.hpp | 213 ------------ .../custom_msgs/geometry_msgs/msg/vector3.hpp | 272 ---------------- 11 files changed, 2 insertions(+), 1353 deletions(-) delete mode 100644 workspace/custom_msgs/geometry_msgs/msg/Point.msg delete mode 100644 workspace/custom_msgs/geometry_msgs/msg/Pose.msg delete mode 100644 workspace/custom_msgs/geometry_msgs/msg/Quaternion.msg delete mode 100644 workspace/custom_msgs/geometry_msgs/msg/Twist.msg delete mode 100644 workspace/custom_msgs/geometry_msgs/msg/Vector3.msg delete mode 100644 workspace/custom_msgs/geometry_msgs/msg/point.hpp delete mode 100644 workspace/custom_msgs/geometry_msgs/msg/pose.hpp delete mode 100644 workspace/custom_msgs/geometry_msgs/msg/quaternion.hpp delete mode 100644 workspace/custom_msgs/geometry_msgs/msg/twist.hpp delete mode 100644 workspace/custom_msgs/geometry_msgs/msg/vector3.hpp diff --git a/README.md b/README.md index 5f8b708..e3e7f76 100644 --- a/README.md +++ b/README.md @@ -284,68 +284,8 @@ you also need to edit `CMakeLists.txt` (see details in comment). ## Generating header files for custom MsgTypes -You can use almost any [built-in-types in ROS 2](https://docs.ros.org/en/rolling/Concepts/About-ROS-Interfaces.html#field-types) on the embedded device. - -In additon, you can define a customized message type (e.g., `Twist.msg`) in the same way as in ROS 2, and use its header file for your application. This section describes how to generate header files for your own MsgTypes (`geometry_msgs::msg::Twist` as an example). - -### Prepare .msg files - -`.msg` files are simple text files that describe the fields of a ROS message (see [About ROS 2 interface](https://docs.ros.org/en/rolling/Concepts/About-ROS-Interfaces.html)). In mros2, they are used to generate header files for messages in embedded applications. - -Prepare `Twist.msg` file and make sure it is in `workspace/custom_msgs/geometry_msgs/msg/`. - -``` -$ cat workspace/custom_msgs/geometry_msgs/msg/Twist.msg -geometry_msgs/msg/Vector3 linear -geometry_msgs/msg/Vector3 angular -``` - -In this example, `Twist` has a nested structure with `Vector3` as a child element. So you also need to prepare its file. - -``` -$ cat workspace/custom_msgs/geometry_msgs/msg/Vector3.msg -float64 x -float64 y -float64 z -``` - -### Generate header files - -To generate header files for `Twist` and `Vector3`, run the following command in `workspace/`. - -``` -$ cd workspace -$ python3 ../mros2/mros2_header_generator/header_generator.py geometry_msgs/msg/Twist.msg -``` - -Make sure header files for custom MsgType are generated in `custom_msgs/`. - -``` -$ ls -R custom_msgs/ -custom_msgs/: -geometry_msgs - -custom_msgs/geometry_msgs: -msg - -custom_msgs/geometry_msgs/msg: -twist.hpp vector3.hpp Twist.msg Vector3.msg -``` - -You can now use them in your applicaton like this. - -``` -#include "mros2.hpp" -#include "mros2-platform.hpp" -#include "geometry_msgs/msg/vector3.hpp" -#include "geometry_msgs/msg/twist.hpp" - -int main(int argc, char * argv[]) -{ - - pub = node.create_publisher("cmd_vel", 10); - -``` +If you want to use your own customized message type followed by the ROS 2 manner, please refer to [mros2#generating-header-files-for-custom-msgtypes](https://github.com/mROS-base/mros2#generating-header-files-for-custom-msgtypes) section. +(this section was moved because it is common feature for mROS 2). ## Tips 1: Configure the network diff --git a/workspace/custom_msgs/geometry_msgs/msg/Point.msg b/workspace/custom_msgs/geometry_msgs/msg/Point.msg deleted file mode 100644 index 681257d..0000000 --- a/workspace/custom_msgs/geometry_msgs/msg/Point.msg +++ /dev/null @@ -1,3 +0,0 @@ -float64 x -float64 y -float64 z \ No newline at end of file diff --git a/workspace/custom_msgs/geometry_msgs/msg/Pose.msg b/workspace/custom_msgs/geometry_msgs/msg/Pose.msg deleted file mode 100644 index 21eed4b..0000000 --- a/workspace/custom_msgs/geometry_msgs/msg/Pose.msg +++ /dev/null @@ -1,2 +0,0 @@ -geometry_msgs/msg/Point position -geometry_msgs/msg/Quaternion orientation \ No newline at end of file diff --git a/workspace/custom_msgs/geometry_msgs/msg/Quaternion.msg b/workspace/custom_msgs/geometry_msgs/msg/Quaternion.msg deleted file mode 100644 index e6c4bed..0000000 --- a/workspace/custom_msgs/geometry_msgs/msg/Quaternion.msg +++ /dev/null @@ -1,4 +0,0 @@ -float64 x -float64 y -float64 z -float64 w \ No newline at end of file diff --git a/workspace/custom_msgs/geometry_msgs/msg/Twist.msg b/workspace/custom_msgs/geometry_msgs/msg/Twist.msg deleted file mode 100644 index a888447..0000000 --- a/workspace/custom_msgs/geometry_msgs/msg/Twist.msg +++ /dev/null @@ -1,2 +0,0 @@ -geometry_msgs/msg/Vector3 linear -geometry_msgs/msg/Vector3 angular \ No newline at end of file diff --git a/workspace/custom_msgs/geometry_msgs/msg/Vector3.msg b/workspace/custom_msgs/geometry_msgs/msg/Vector3.msg deleted file mode 100644 index 681257d..0000000 --- a/workspace/custom_msgs/geometry_msgs/msg/Vector3.msg +++ /dev/null @@ -1,3 +0,0 @@ -float64 x -float64 y -float64 z \ No newline at end of file diff --git a/workspace/custom_msgs/geometry_msgs/msg/point.hpp b/workspace/custom_msgs/geometry_msgs/msg/point.hpp deleted file mode 100644 index f2808a8..0000000 --- a/workspace/custom_msgs/geometry_msgs/msg/point.hpp +++ /dev/null @@ -1,272 +0,0 @@ -#ifndef _GEOMETRY_MSGS_MSG_POINT_H -#define _GEOMETRY_MSGS_MSG_POINT_H - -#include -#include - -using namespace std; - -namespace geometry_msgs -{ -namespace msg -{ -class Point -{ -public: - uint32_t cntPub = 0; - uint32_t cntSub = 0; - uint32_t idxSerialized = 0; - - typedef std::pair FragCopyReturnType; - - template - uint32_t copyPrimToFragBufLocal(uint8_t*& addrPtr, - const uint32_t cntPub, - const uint32_t size, - const T& data) - { - uint32_t lenPad = (0 == (cntPub % sizeof(T))) ? - 0 : (sizeof(T) - (cntPub % sizeof(T))); // this doesn't get along with float128. - if ( size < sizeof(T) ) { - // There are no enough space. - return 0; - } - // Put padding space - for(int i = 0; i < lenPad; i++){ - *addrPtr = 0; - addrPtr += 1; - } - // Store serialzed value. - memcpy(addrPtr, &data, sizeof(T)); - addrPtr += sizeof(T); - - return sizeof(T) + lenPad; - } - - template - FragCopyReturnType copyArrayToFragBufLocal(uint8_t*& addrPtr, - const uint32_t size, - T& data, - uint32_t& cntPubMemberLocal) - { - uint32_t pubDataSize = data.size(); - uint32_t cntLocalFrag = 0; - - if (cntPubMemberLocal < sizeof(uint32_t)) { - if (size < sizeof(uint32_t)) { - return {false, 0}; - } - memcpy(addrPtr, &pubDataSize, sizeof(uint32_t)); - addrPtr += sizeof(uint32_t); - cntPubMemberLocal += sizeof(uint32_t); - cntLocalFrag += sizeof(uint32_t); - } - - uint32_t cntFrag = (cntPubMemberLocal - sizeof(uint32_t)); - // cntPubMemberLocal > 4 here - uint32_t tmp = std::min(pubDataSize - cntFrag, size - cntLocalFrag); - if (0 < tmp) { - memcpy(addrPtr, data.data() + cntFrag, tmp); - addrPtr += tmp; - cntPubMemberLocal += tmp; - cntLocalFrag += tmp; - } - - return {(cntPubMemberLocal - sizeof(uint32_t)) >= pubDataSize, cntLocalFrag}; - } - - - double x -; - - double y -; - - double z; - - - uint32_t copyToBuf(uint8_t *addrPtr) - { - uint32_t tmpPub = 0; - uint32_t arraySize; - uint32_t stringSize; - - - - if (cntPub%8 > 0){ - for(int i=0; i<(8-(cntPub%8)) ; i++){ - *addrPtr = 0; - addrPtr += 1; - } - cntPub += 8-(cntPub%8); - } - - memcpy(addrPtr,&x -,8); - addrPtr += 8; - cntPub += 8; - - - - - - if (cntPub%8 > 0){ - for(int i=0; i<(8-(cntPub%8)) ; i++){ - *addrPtr = 0; - addrPtr += 1; - } - cntPub += 8-(cntPub%8); - } - - memcpy(addrPtr,&y -,8); - addrPtr += 8; - cntPub += 8; - - - - - - if (cntPub%8 > 0){ - for(int i=0; i<(8-(cntPub%8)) ; i++){ - *addrPtr = 0; - addrPtr += 1; - } - cntPub += 8-(cntPub%8); - } - - memcpy(addrPtr,&z,8); - addrPtr += 8; - cntPub += 8; - - - - - return cntPub; - } - - uint32_t copyFromBuf(const uint8_t *addrPtr) { - uint32_t tmpSub = 0; - uint32_t arraySize; - uint32_t stringSize; - - - - - if (cntSub%8 > 0){ - for(int i=0; i<(8-(cntSub%8)) ; i++){ - addrPtr += 1; - } - cntSub += 8-(cntSub%8); - } - - memcpy(&x -,addrPtr,8); - addrPtr += 8; - cntSub += 8; - - - - - if (cntSub%8 > 0){ - for(int i=0; i<(8-(cntSub%8)) ; i++){ - addrPtr += 1; - } - cntSub += 8-(cntSub%8); - } - - memcpy(&y -,addrPtr,8); - addrPtr += 8; - cntSub += 8; - - - - - if (cntSub%8 > 0){ - for(int i=0; i<(8-(cntSub%8)) ; i++){ - addrPtr += 1; - } - cntSub += 8-(cntSub%8); - } - - memcpy(&z,addrPtr,8); - addrPtr += 8; - cntSub += 8; - - - - return cntSub; - } - - void memAlign(uint8_t *addrPtr){ - if (cntPub%4 > 0){ - addrPtr += cntPub; - for(int i=0; i<(4-(cntPub%4)) ; i++){ - *addrPtr = 0; - addrPtr += 1; - } - cntPub += 4-(cntPub%4); - } - return; - } - - uint32_t getTotalSize(){ - uint32_t tmpCntPub = cntPub; - cntPub = 0; - return tmpCntPub ; - } - - uint32_t getPubCnt() - { - return cntPub; - } - - uint32_t calcRawTotalSize() - { - // TODO: store template code here - return 0; - } - - uint32_t calcTotalSize() - { - uint32_t tmp; - tmp = 4 // CDR encoding version. - + calcRawTotalSize(); - tmp += ( 0 == (tmp % 4) ? // Padding - 0 : (4 - (tmp % 4)) ); - return tmp; - } - - void resetCount() - { - cntPub = 0; - cntSub = 0; - idxSerialized = 0; - // TODO: store template code here - return; - } - - FragCopyReturnType copyToFragBuf(uint8_t *addrPtr, uint32_t size) - { - // TODO: store template code here - return {false, 0}; - } -private: - std::string type_name = "geometry_msgs::msg::dds_::Point"; -}; -}; -} - -namespace message_traits -{ -template<> -struct TypeName { - static const char* value() - { - return "geometry_msgs::msg::dds_::Point_"; - } -}; -} - -#endif \ No newline at end of file diff --git a/workspace/custom_msgs/geometry_msgs/msg/pose.hpp b/workspace/custom_msgs/geometry_msgs/msg/pose.hpp deleted file mode 100644 index 5b0f4f4..0000000 --- a/workspace/custom_msgs/geometry_msgs/msg/pose.hpp +++ /dev/null @@ -1,213 +0,0 @@ -#ifndef _GEOMETRY_MSGS_MSG_POSE_H -#define _GEOMETRY_MSGS_MSG_POSE_H - -#include -#include -#include "geometry_msgs/msg/point.hpp" -#include "geometry_msgs/msg/quaternion.hpp" - -using namespace std; - -namespace geometry_msgs -{ -namespace msg -{ -class Pose -{ -public: - uint32_t cntPub = 0; - uint32_t cntSub = 0; - uint32_t idxSerialized = 0; - - typedef std::pair FragCopyReturnType; - - template - uint32_t copyPrimToFragBufLocal(uint8_t*& addrPtr, - const uint32_t cntPub, - const uint32_t size, - const T& data) - { - uint32_t lenPad = (0 == (cntPub % sizeof(T))) ? - 0 : (sizeof(T) - (cntPub % sizeof(T))); // this doesn't get along with float128. - if ( size < sizeof(T) ) { - // There are no enough space. - return 0; - } - // Put padding space - for(int i = 0; i < lenPad; i++){ - *addrPtr = 0; - addrPtr += 1; - } - // Store serialzed value. - memcpy(addrPtr, &data, sizeof(T)); - addrPtr += sizeof(T); - - return sizeof(T) + lenPad; - } - - template - FragCopyReturnType copyArrayToFragBufLocal(uint8_t*& addrPtr, - const uint32_t size, - T& data, - uint32_t& cntPubMemberLocal) - { - uint32_t pubDataSize = data.size(); - uint32_t cntLocalFrag = 0; - - if (cntPubMemberLocal < sizeof(uint32_t)) { - if (size < sizeof(uint32_t)) { - return {false, 0}; - } - memcpy(addrPtr, &pubDataSize, sizeof(uint32_t)); - addrPtr += sizeof(uint32_t); - cntPubMemberLocal += sizeof(uint32_t); - cntLocalFrag += sizeof(uint32_t); - } - - uint32_t cntFrag = (cntPubMemberLocal - sizeof(uint32_t)); - // cntPubMemberLocal > 4 here - uint32_t tmp = std::min(pubDataSize - cntFrag, size - cntLocalFrag); - if (0 < tmp) { - memcpy(addrPtr, data.data() + cntFrag, tmp); - addrPtr += tmp; - cntPubMemberLocal += tmp; - cntLocalFrag += tmp; - } - - return {(cntPubMemberLocal - sizeof(uint32_t)) >= pubDataSize, cntLocalFrag}; - } - - - geometry_msgs::msg::Point position -; - - geometry_msgs::msg::Quaternion orientation; - - - uint32_t copyToBuf(uint8_t *addrPtr) - { - uint32_t tmpPub = 0; - uint32_t arraySize; - uint32_t stringSize; - - - - tmpPub = position -.copyToBuf(addrPtr); - cntPub += tmpPub; - addrPtr += tmpPub; - - - - - - tmpPub = orientation.copyToBuf(addrPtr); - cntPub += tmpPub; - addrPtr += tmpPub; - - - - - return cntPub; - } - - uint32_t copyFromBuf(const uint8_t *addrPtr) { - uint32_t tmpSub = 0; - uint32_t arraySize; - uint32_t stringSize; - - - - - tmpSub = position -.copyFromBuf(addrPtr); - cntSub += tmpSub; - addrPtr += tmpSub; - - - - - - - tmpSub = orientation.copyFromBuf(addrPtr); - cntSub += tmpSub; - addrPtr += tmpSub; - - - - - - return cntSub; - } - - void memAlign(uint8_t *addrPtr){ - if (cntPub%4 > 0){ - addrPtr += cntPub; - for(int i=0; i<(4-(cntPub%4)) ; i++){ - *addrPtr = 0; - addrPtr += 1; - } - cntPub += 4-(cntPub%4); - } - return; - } - - uint32_t getTotalSize(){ - uint32_t tmpCntPub = cntPub; - cntPub = 0; - return tmpCntPub ; - } - - uint32_t getPubCnt() - { - return cntPub; - } - - uint32_t calcRawTotalSize() - { - // TODO: store template code here - return 0; - } - - uint32_t calcTotalSize() - { - uint32_t tmp; - tmp = 4 // CDR encoding version. - + calcRawTotalSize(); - tmp += ( 0 == (tmp % 4) ? // Padding - 0 : (4 - (tmp % 4)) ); - return tmp; - } - - void resetCount() - { - cntPub = 0; - cntSub = 0; - idxSerialized = 0; - // TODO: store template code here - return; - } - - FragCopyReturnType copyToFragBuf(uint8_t *addrPtr, uint32_t size) - { - // TODO: store template code here - return {false, 0}; - } -private: - std::string type_name = "geometry_msgs::msg::dds_::Pose"; -}; -}; -} - -namespace message_traits -{ -template<> -struct TypeName { - static const char* value() - { - return "geometry_msgs::msg::dds_::Pose_"; - } -}; -} - -#endif \ No newline at end of file diff --git a/workspace/custom_msgs/geometry_msgs/msg/quaternion.hpp b/workspace/custom_msgs/geometry_msgs/msg/quaternion.hpp deleted file mode 100644 index 80f0823..0000000 --- a/workspace/custom_msgs/geometry_msgs/msg/quaternion.hpp +++ /dev/null @@ -1,307 +0,0 @@ -#ifndef _GEOMETRY_MSGS_MSG_QUATERNION_H -#define _GEOMETRY_MSGS_MSG_QUATERNION_H - -#include -#include - -using namespace std; - -namespace geometry_msgs -{ -namespace msg -{ -class Quaternion -{ -public: - uint32_t cntPub = 0; - uint32_t cntSub = 0; - uint32_t idxSerialized = 0; - - typedef std::pair FragCopyReturnType; - - template - uint32_t copyPrimToFragBufLocal(uint8_t*& addrPtr, - const uint32_t cntPub, - const uint32_t size, - const T& data) - { - uint32_t lenPad = (0 == (cntPub % sizeof(T))) ? - 0 : (sizeof(T) - (cntPub % sizeof(T))); // this doesn't get along with float128. - if ( size < sizeof(T) ) { - // There are no enough space. - return 0; - } - // Put padding space - for(int i = 0; i < lenPad; i++){ - *addrPtr = 0; - addrPtr += 1; - } - // Store serialzed value. - memcpy(addrPtr, &data, sizeof(T)); - addrPtr += sizeof(T); - - return sizeof(T) + lenPad; - } - - template - FragCopyReturnType copyArrayToFragBufLocal(uint8_t*& addrPtr, - const uint32_t size, - T& data, - uint32_t& cntPubMemberLocal) - { - uint32_t pubDataSize = data.size(); - uint32_t cntLocalFrag = 0; - - if (cntPubMemberLocal < sizeof(uint32_t)) { - if (size < sizeof(uint32_t)) { - return {false, 0}; - } - memcpy(addrPtr, &pubDataSize, sizeof(uint32_t)); - addrPtr += sizeof(uint32_t); - cntPubMemberLocal += sizeof(uint32_t); - cntLocalFrag += sizeof(uint32_t); - } - - uint32_t cntFrag = (cntPubMemberLocal - sizeof(uint32_t)); - // cntPubMemberLocal > 4 here - uint32_t tmp = std::min(pubDataSize - cntFrag, size - cntLocalFrag); - if (0 < tmp) { - memcpy(addrPtr, data.data() + cntFrag, tmp); - addrPtr += tmp; - cntPubMemberLocal += tmp; - cntLocalFrag += tmp; - } - - return {(cntPubMemberLocal - sizeof(uint32_t)) >= pubDataSize, cntLocalFrag}; - } - - - double x -; - - double y -; - - double z -; - - double w; - - - uint32_t copyToBuf(uint8_t *addrPtr) - { - uint32_t tmpPub = 0; - uint32_t arraySize; - uint32_t stringSize; - - - - if (cntPub%8 > 0){ - for(int i=0; i<(8-(cntPub%8)) ; i++){ - *addrPtr = 0; - addrPtr += 1; - } - cntPub += 8-(cntPub%8); - } - - memcpy(addrPtr,&x -,8); - addrPtr += 8; - cntPub += 8; - - - - - - if (cntPub%8 > 0){ - for(int i=0; i<(8-(cntPub%8)) ; i++){ - *addrPtr = 0; - addrPtr += 1; - } - cntPub += 8-(cntPub%8); - } - - memcpy(addrPtr,&y -,8); - addrPtr += 8; - cntPub += 8; - - - - - - if (cntPub%8 > 0){ - for(int i=0; i<(8-(cntPub%8)) ; i++){ - *addrPtr = 0; - addrPtr += 1; - } - cntPub += 8-(cntPub%8); - } - - memcpy(addrPtr,&z -,8); - addrPtr += 8; - cntPub += 8; - - - - - - if (cntPub%8 > 0){ - for(int i=0; i<(8-(cntPub%8)) ; i++){ - *addrPtr = 0; - addrPtr += 1; - } - cntPub += 8-(cntPub%8); - } - - memcpy(addrPtr,&w,8); - addrPtr += 8; - cntPub += 8; - - - - - return cntPub; - } - - uint32_t copyFromBuf(const uint8_t *addrPtr) { - uint32_t tmpSub = 0; - uint32_t arraySize; - uint32_t stringSize; - - - - - if (cntSub%8 > 0){ - for(int i=0; i<(8-(cntSub%8)) ; i++){ - addrPtr += 1; - } - cntSub += 8-(cntSub%8); - } - - memcpy(&x -,addrPtr,8); - addrPtr += 8; - cntSub += 8; - - - - - if (cntSub%8 > 0){ - for(int i=0; i<(8-(cntSub%8)) ; i++){ - addrPtr += 1; - } - cntSub += 8-(cntSub%8); - } - - memcpy(&y -,addrPtr,8); - addrPtr += 8; - cntSub += 8; - - - - - if (cntSub%8 > 0){ - for(int i=0; i<(8-(cntSub%8)) ; i++){ - addrPtr += 1; - } - cntSub += 8-(cntSub%8); - } - - memcpy(&z -,addrPtr,8); - addrPtr += 8; - cntSub += 8; - - - - - if (cntSub%8 > 0){ - for(int i=0; i<(8-(cntSub%8)) ; i++){ - addrPtr += 1; - } - cntSub += 8-(cntSub%8); - } - - memcpy(&w,addrPtr,8); - addrPtr += 8; - cntSub += 8; - - - - return cntSub; - } - - void memAlign(uint8_t *addrPtr){ - if (cntPub%4 > 0){ - addrPtr += cntPub; - for(int i=0; i<(4-(cntPub%4)) ; i++){ - *addrPtr = 0; - addrPtr += 1; - } - cntPub += 4-(cntPub%4); - } - return; - } - - uint32_t getTotalSize(){ - uint32_t tmpCntPub = cntPub; - cntPub = 0; - return tmpCntPub ; - } - - uint32_t getPubCnt() - { - return cntPub; - } - - uint32_t calcRawTotalSize() - { - // TODO: store template code here - return 0; - } - - uint32_t calcTotalSize() - { - uint32_t tmp; - tmp = 4 // CDR encoding version. - + calcRawTotalSize(); - tmp += ( 0 == (tmp % 4) ? // Padding - 0 : (4 - (tmp % 4)) ); - return tmp; - } - - void resetCount() - { - cntPub = 0; - cntSub = 0; - idxSerialized = 0; - // TODO: store template code here - return; - } - - FragCopyReturnType copyToFragBuf(uint8_t *addrPtr, uint32_t size) - { - // TODO: store template code here - return {false, 0}; - } -private: - std::string type_name = "geometry_msgs::msg::dds_::Quaternion"; -}; -}; -} - -namespace message_traits -{ -template<> -struct TypeName { - static const char* value() - { - return "geometry_msgs::msg::dds_::Quaternion_"; - } -}; -} - -#endif \ No newline at end of file diff --git a/workspace/custom_msgs/geometry_msgs/msg/twist.hpp b/workspace/custom_msgs/geometry_msgs/msg/twist.hpp deleted file mode 100644 index d8a207d..0000000 --- a/workspace/custom_msgs/geometry_msgs/msg/twist.hpp +++ /dev/null @@ -1,213 +0,0 @@ -#ifndef _GEOMETRY_MSGS_MSG_TWIST_H -#define _GEOMETRY_MSGS_MSG_TWIST_H - -#include -#include -#include "geometry_msgs/msg/vector3.hpp" -#include "geometry_msgs/msg/vector3.hpp" - -using namespace std; - -namespace geometry_msgs -{ -namespace msg -{ -class Twist -{ -public: - uint32_t cntPub = 0; - uint32_t cntSub = 0; - uint32_t idxSerialized = 0; - - typedef std::pair FragCopyReturnType; - - template - uint32_t copyPrimToFragBufLocal(uint8_t*& addrPtr, - const uint32_t cntPub, - const uint32_t size, - const T& data) - { - uint32_t lenPad = (0 == (cntPub % sizeof(T))) ? - 0 : (sizeof(T) - (cntPub % sizeof(T))); // this doesn't get along with float128. - if ( size < sizeof(T) ) { - // There are no enough space. - return 0; - } - // Put padding space - for(int i = 0; i < lenPad; i++){ - *addrPtr = 0; - addrPtr += 1; - } - // Store serialzed value. - memcpy(addrPtr, &data, sizeof(T)); - addrPtr += sizeof(T); - - return sizeof(T) + lenPad; - } - - template - FragCopyReturnType copyArrayToFragBufLocal(uint8_t*& addrPtr, - const uint32_t size, - T& data, - uint32_t& cntPubMemberLocal) - { - uint32_t pubDataSize = data.size(); - uint32_t cntLocalFrag = 0; - - if (cntPubMemberLocal < sizeof(uint32_t)) { - if (size < sizeof(uint32_t)) { - return {false, 0}; - } - memcpy(addrPtr, &pubDataSize, sizeof(uint32_t)); - addrPtr += sizeof(uint32_t); - cntPubMemberLocal += sizeof(uint32_t); - cntLocalFrag += sizeof(uint32_t); - } - - uint32_t cntFrag = (cntPubMemberLocal - sizeof(uint32_t)); - // cntPubMemberLocal > 4 here - uint32_t tmp = std::min(pubDataSize - cntFrag, size - cntLocalFrag); - if (0 < tmp) { - memcpy(addrPtr, data.data() + cntFrag, tmp); - addrPtr += tmp; - cntPubMemberLocal += tmp; - cntLocalFrag += tmp; - } - - return {(cntPubMemberLocal - sizeof(uint32_t)) >= pubDataSize, cntLocalFrag}; - } - - - geometry_msgs::msg::Vector3 linear -; - - geometry_msgs::msg::Vector3 angular; - - - uint32_t copyToBuf(uint8_t *addrPtr) - { - uint32_t tmpPub = 0; - uint32_t arraySize; - uint32_t stringSize; - - - - tmpPub = linear -.copyToBuf(addrPtr); - cntPub += tmpPub; - addrPtr += tmpPub; - - - - - - tmpPub = angular.copyToBuf(addrPtr); - cntPub += tmpPub; - addrPtr += tmpPub; - - - - - return cntPub; - } - - uint32_t copyFromBuf(const uint8_t *addrPtr) { - uint32_t tmpSub = 0; - uint32_t arraySize; - uint32_t stringSize; - - - - - tmpSub = linear -.copyFromBuf(addrPtr); - cntSub += tmpSub; - addrPtr += tmpSub; - - - - - - - tmpSub = angular.copyFromBuf(addrPtr); - cntSub += tmpSub; - addrPtr += tmpSub; - - - - - - return cntSub; - } - - void memAlign(uint8_t *addrPtr){ - if (cntPub%4 > 0){ - addrPtr += cntPub; - for(int i=0; i<(4-(cntPub%4)) ; i++){ - *addrPtr = 0; - addrPtr += 1; - } - cntPub += 4-(cntPub%4); - } - return; - } - - uint32_t getTotalSize(){ - uint32_t tmpCntPub = cntPub; - cntPub = 0; - return tmpCntPub ; - } - - uint32_t getPubCnt() - { - return cntPub; - } - - uint32_t calcRawTotalSize() - { - // TODO: store template code here - return 0; - } - - uint32_t calcTotalSize() - { - uint32_t tmp; - tmp = 4 // CDR encoding version. - + calcRawTotalSize(); - tmp += ( 0 == (tmp % 4) ? // Padding - 0 : (4 - (tmp % 4)) ); - return tmp; - } - - void resetCount() - { - cntPub = 0; - cntSub = 0; - idxSerialized = 0; - // TODO: store template code here - return; - } - - FragCopyReturnType copyToFragBuf(uint8_t *addrPtr, uint32_t size) - { - // TODO: store template code here - return {false, 0}; - } -private: - std::string type_name = "geometry_msgs::msg::dds_::Twist"; -}; -}; -} - -namespace message_traits -{ -template<> -struct TypeName { - static const char* value() - { - return "geometry_msgs::msg::dds_::Twist_"; - } -}; -} - -#endif \ No newline at end of file diff --git a/workspace/custom_msgs/geometry_msgs/msg/vector3.hpp b/workspace/custom_msgs/geometry_msgs/msg/vector3.hpp deleted file mode 100644 index 89bc8e1..0000000 --- a/workspace/custom_msgs/geometry_msgs/msg/vector3.hpp +++ /dev/null @@ -1,272 +0,0 @@ -#ifndef _GEOMETRY_MSGS_MSG_VECTOR3_H -#define _GEOMETRY_MSGS_MSG_VECTOR3_H - -#include -#include - -using namespace std; - -namespace geometry_msgs -{ -namespace msg -{ -class Vector3 -{ -public: - uint32_t cntPub = 0; - uint32_t cntSub = 0; - uint32_t idxSerialized = 0; - - typedef std::pair FragCopyReturnType; - - template - uint32_t copyPrimToFragBufLocal(uint8_t*& addrPtr, - const uint32_t cntPub, - const uint32_t size, - const T& data) - { - uint32_t lenPad = (0 == (cntPub % sizeof(T))) ? - 0 : (sizeof(T) - (cntPub % sizeof(T))); // this doesn't get along with float128. - if ( size < sizeof(T) ) { - // There are no enough space. - return 0; - } - // Put padding space - for(int i = 0; i < lenPad; i++){ - *addrPtr = 0; - addrPtr += 1; - } - // Store serialzed value. - memcpy(addrPtr, &data, sizeof(T)); - addrPtr += sizeof(T); - - return sizeof(T) + lenPad; - } - - template - FragCopyReturnType copyArrayToFragBufLocal(uint8_t*& addrPtr, - const uint32_t size, - T& data, - uint32_t& cntPubMemberLocal) - { - uint32_t pubDataSize = data.size(); - uint32_t cntLocalFrag = 0; - - if (cntPubMemberLocal < sizeof(uint32_t)) { - if (size < sizeof(uint32_t)) { - return {false, 0}; - } - memcpy(addrPtr, &pubDataSize, sizeof(uint32_t)); - addrPtr += sizeof(uint32_t); - cntPubMemberLocal += sizeof(uint32_t); - cntLocalFrag += sizeof(uint32_t); - } - - uint32_t cntFrag = (cntPubMemberLocal - sizeof(uint32_t)); - // cntPubMemberLocal > 4 here - uint32_t tmp = std::min(pubDataSize - cntFrag, size - cntLocalFrag); - if (0 < tmp) { - memcpy(addrPtr, data.data() + cntFrag, tmp); - addrPtr += tmp; - cntPubMemberLocal += tmp; - cntLocalFrag += tmp; - } - - return {(cntPubMemberLocal - sizeof(uint32_t)) >= pubDataSize, cntLocalFrag}; - } - - - double x -; - - double y -; - - double z; - - - uint32_t copyToBuf(uint8_t *addrPtr) - { - uint32_t tmpPub = 0; - uint32_t arraySize; - uint32_t stringSize; - - - - if (cntPub%8 > 0){ - for(int i=0; i<(8-(cntPub%8)) ; i++){ - *addrPtr = 0; - addrPtr += 1; - } - cntPub += 8-(cntPub%8); - } - - memcpy(addrPtr,&x -,8); - addrPtr += 8; - cntPub += 8; - - - - - - if (cntPub%8 > 0){ - for(int i=0; i<(8-(cntPub%8)) ; i++){ - *addrPtr = 0; - addrPtr += 1; - } - cntPub += 8-(cntPub%8); - } - - memcpy(addrPtr,&y -,8); - addrPtr += 8; - cntPub += 8; - - - - - - if (cntPub%8 > 0){ - for(int i=0; i<(8-(cntPub%8)) ; i++){ - *addrPtr = 0; - addrPtr += 1; - } - cntPub += 8-(cntPub%8); - } - - memcpy(addrPtr,&z,8); - addrPtr += 8; - cntPub += 8; - - - - - return cntPub; - } - - uint32_t copyFromBuf(const uint8_t *addrPtr) { - uint32_t tmpSub = 0; - uint32_t arraySize; - uint32_t stringSize; - - - - - if (cntSub%8 > 0){ - for(int i=0; i<(8-(cntSub%8)) ; i++){ - addrPtr += 1; - } - cntSub += 8-(cntSub%8); - } - - memcpy(&x -,addrPtr,8); - addrPtr += 8; - cntSub += 8; - - - - - if (cntSub%8 > 0){ - for(int i=0; i<(8-(cntSub%8)) ; i++){ - addrPtr += 1; - } - cntSub += 8-(cntSub%8); - } - - memcpy(&y -,addrPtr,8); - addrPtr += 8; - cntSub += 8; - - - - - if (cntSub%8 > 0){ - for(int i=0; i<(8-(cntSub%8)) ; i++){ - addrPtr += 1; - } - cntSub += 8-(cntSub%8); - } - - memcpy(&z,addrPtr,8); - addrPtr += 8; - cntSub += 8; - - - - return cntSub; - } - - void memAlign(uint8_t *addrPtr){ - if (cntPub%4 > 0){ - addrPtr += cntPub; - for(int i=0; i<(4-(cntPub%4)) ; i++){ - *addrPtr = 0; - addrPtr += 1; - } - cntPub += 4-(cntPub%4); - } - return; - } - - uint32_t getTotalSize(){ - uint32_t tmpCntPub = cntPub; - cntPub = 0; - return tmpCntPub ; - } - - uint32_t getPubCnt() - { - return cntPub; - } - - uint32_t calcRawTotalSize() - { - // TODO: store template code here - return 0; - } - - uint32_t calcTotalSize() - { - uint32_t tmp; - tmp = 4 // CDR encoding version. - + calcRawTotalSize(); - tmp += ( 0 == (tmp % 4) ? // Padding - 0 : (4 - (tmp % 4)) ); - return tmp; - } - - void resetCount() - { - cntPub = 0; - cntSub = 0; - idxSerialized = 0; - // TODO: store template code here - return; - } - - FragCopyReturnType copyToFragBuf(uint8_t *addrPtr, uint32_t size) - { - // TODO: store template code here - return {false, 0}; - } -private: - std::string type_name = "geometry_msgs::msg::dds_::Vector3"; -}; -}; -} - -namespace message_traits -{ -template<> -struct TypeName { - static const char* value() - { - return "geometry_msgs::msg::dds_::Vector3_"; - } -}; -} - -#endif \ No newline at end of file