message_conversion.cpp 4.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168
  1. /*
  2. * Copyright 2015-2019 Autoware Foundation. All rights reserved.
  3. *
  4. * Licensed under the Apache License, Version 2.0 (the "License");
  5. * you may not use this file except in compliance with the License.
  6. * You may obtain a copy of the License at
  7. *
  8. * http://www.apache.org/licenses/LICENSE-2.0
  9. *
  10. * Unless required by applicable law or agreed to in writing, software
  11. * distributed under the License is distributed on an "AS IS" BASIS,
  12. * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
  13. * See the License for the specific language governing permissions and
  14. * limitations under the License.
  15. *
  16. * Authors: Simon Thompson, Ryohsuke Mitsudome
  17. */
  18. #include <lanelet2_core/primitives/Lanelet.h>
  19. #include <lanelet2_io/Exceptions.h>
  20. #include <lanelet2_io/Projection.h>
  21. #include <lanelet2_io/io_handlers/OsmFile.h>
  22. #include <lanelet2_io/io_handlers/OsmHandler.h>
  23. #include <lanelet2_io/io_handlers/Serialize.h>
  24. #include <lanelet2_projection/UTM.h>
  25. #include <ros/ros.h>
  26. #include <lanelet2_extension/projection/mgrs_projector.h>
  27. #include <lanelet2_extension/utility/message_conversion.h>
  28. #include <boost/archive/binary_iarchive.hpp>
  29. #include <boost/archive/binary_oarchive.hpp>
  30. #include <sstream>
  31. #include <string>
  32. namespace lanelet
  33. {
  34. namespace utils
  35. {
  36. namespace conversion
  37. {
  38. void toBinMsg(const lanelet::LaneletMapPtr& map, autoware_lanelet2_msgs::MapBin* msg)
  39. {
  40. if (msg == nullptr)
  41. {
  42. ROS_ERROR_STREAM(__FUNCTION__ << "msg is null pointer!");
  43. return;
  44. }
  45. std::stringstream ss;
  46. boost::archive::binary_oarchive oa(ss);
  47. oa << *map;
  48. auto id_counter = lanelet::utils::getId();
  49. oa << id_counter;
  50. std::string data_str(ss.str());
  51. msg->data.clear();
  52. msg->data.assign(data_str.begin(), data_str.end());
  53. }
  54. void fromBinMsg(const autoware_lanelet2_msgs::MapBin& msg, lanelet::LaneletMapPtr map)
  55. {
  56. if (!map)
  57. {
  58. ROS_ERROR_STREAM(__FUNCTION__ << ": map is null pointer!");
  59. return;
  60. }
  61. std::string data_str;
  62. data_str.assign(msg.data.begin(), msg.data.end());
  63. std::stringstream ss;
  64. ss << data_str;
  65. boost::archive::binary_iarchive oa(ss);
  66. oa >> *map;
  67. lanelet::Id id_counter;
  68. oa >> id_counter;
  69. lanelet::utils::registerId(id_counter);
  70. // *map = std::move(laneletMap);
  71. }
  72. void toGeomMsgPt(const geometry_msgs::Point32& src, geometry_msgs::Point* dst)
  73. {
  74. if (dst == nullptr)
  75. {
  76. ROS_ERROR_STREAM(__FUNCTION__ << "pointer is null!");
  77. return;
  78. }
  79. dst->x = src.x;
  80. dst->y = src.y;
  81. dst->z = src.z;
  82. }
  83. void toGeomMsgPt(const Eigen::Vector3d& src, geometry_msgs::Point* dst)
  84. {
  85. if (dst == nullptr)
  86. {
  87. ROS_ERROR_STREAM(__FUNCTION__ << "pointer is null!");
  88. return;
  89. }
  90. dst->x = src.x();
  91. dst->y = src.y();
  92. dst->z = src.z();
  93. }
  94. void toGeomMsgPt(const lanelet::ConstPoint3d& src, geometry_msgs::Point* dst)
  95. {
  96. if (dst == nullptr)
  97. {
  98. ROS_ERROR_STREAM(__FUNCTION__ << "pointer is null!");
  99. return;
  100. }
  101. dst->x = src.x();
  102. dst->y = src.y();
  103. dst->z = src.z();
  104. }
  105. void toGeomMsgPt(const lanelet::ConstPoint2d& src, geometry_msgs::Point* dst)
  106. {
  107. if (dst == nullptr)
  108. {
  109. ROS_ERROR_STREAM(__FUNCTION__ << "pointer is null!");
  110. return;
  111. }
  112. dst->x = src.x();
  113. dst->y = src.y();
  114. dst->z = 0;
  115. }
  116. void toGeomMsgPt32(const Eigen::Vector3d& src, geometry_msgs::Point32* dst)
  117. {
  118. if (dst == nullptr)
  119. {
  120. ROS_ERROR_STREAM(__FUNCTION__ << "pointer is null!");
  121. return;
  122. }
  123. dst->x = src.x();
  124. dst->y = src.y();
  125. dst->z = src.z();
  126. }
  127. geometry_msgs::Point toGeomMsgPt(const geometry_msgs::Point32& src)
  128. {
  129. geometry_msgs::Point dst;
  130. toGeomMsgPt(src, &dst);
  131. return dst;
  132. }
  133. geometry_msgs::Point toGeomMsgPt(const Eigen::Vector3d& src)
  134. {
  135. geometry_msgs::Point dst;
  136. toGeomMsgPt(src, &dst);
  137. return dst;
  138. }
  139. geometry_msgs::Point toGeomMsgPt(const lanelet::ConstPoint3d& src)
  140. {
  141. geometry_msgs::Point dst;
  142. toGeomMsgPt(src, &dst);
  143. return dst;
  144. }
  145. geometry_msgs::Point toGeomMsgPt(const lanelet::ConstPoint2d& src)
  146. {
  147. geometry_msgs::Point dst;
  148. toGeomMsgPt(src, &dst);
  149. return dst;
  150. }
  151. } // namespace conversion
  152. } // namespace utils
  153. } // namespace lanelet