2929#define UR_CLIENT_LIBRARY_DATA_PACKAGE_H_INCLUDED
3030
3131#include < unordered_map>
32+ #include < variant>
3233#include < vector>
3334
3435#include " ur_client_library/types.h"
3536#include " ur_client_library/rtde/rtde_package.h"
36- #include < boost/variant.hpp>
3737
3838namespace urcl
3939{
@@ -59,8 +59,8 @@ enum class RUNTIME_STATE : uint32_t
5959class DataPackage : public RTDEPackage
6060{
6161public:
62- using _rtde_type_variant = boost ::variant<bool , uint8_t , uint32_t , uint64_t , int32_t , double , vector3d_t , vector6d_t ,
63- vector6int32_t , vector6uint32_t , std::string>;
62+ using _rtde_type_variant = std ::variant<bool , uint8_t , uint32_t , uint64_t , int32_t , double , vector3d_t , vector6d_t ,
63+ vector6int32_t , vector6uint32_t , std::string>;
6464
6565 DataPackage () = delete ;
6666
@@ -116,7 +116,6 @@ class DataPackage : public RTDEPackage
116116 *
117117 * \param name The string identifier for the data field as used in the documentation.
118118 * \param val Target variable. Make sure, it's the correct type.
119- * \exception boost::bad_get if the type under given \p name does not match the template type T.
120119 *
121120 * \returns True on success, false if the field cannot be found inside the package.
122121 */
@@ -125,7 +124,7 @@ class DataPackage : public RTDEPackage
125124 {
126125 if (data_.find (name) != data_.end ())
127126 {
128- val = boost::strict_get <T>(data_[name]);
127+ val = std::get <T>(data_[name]);
129128 }
130129 else
131130 {
@@ -141,7 +140,6 @@ class DataPackage : public RTDEPackage
141140 *
142141 * \param name The string identifier for the data field as used in the documentation.
143142 * \param val Target variable. Make sure, it's the correct type.
144- * \exception boost::bad_get if the type under given \p name does not match the template type T.
145143 *
146144 * \returns True on success, false if the field cannot be found inside the package.
147145 */
@@ -152,7 +150,7 @@ class DataPackage : public RTDEPackage
152150
153151 if (data_.find (name) != data_.end ())
154152 {
155- val = std::bitset<N>(boost::strict_get <T>(data_[name]));
153+ val = std::bitset<N>(std::get <T>(data_[name]));
156154 }
157155 else
158156 {
@@ -201,41 +199,6 @@ class DataPackage : public RTDEPackage
201199 uint8_t recipe_id_;
202200 std::unordered_map<std::string, _rtde_type_variant> data_;
203201 std::vector<std::string> recipe_;
204-
205- struct ParseVisitor : public boost ::static_visitor<>
206- {
207- template <typename T>
208- void operator ()(T& d, comm::BinParser& bp) const
209- {
210- bp.parse (d);
211- }
212- };
213- struct StringVisitor : public boost ::static_visitor<std::string>
214- {
215- template <typename T>
216- std::string operator ()(T& d) const
217- {
218- std::stringstream ss;
219- ss << d;
220- return ss.str ();
221- }
222- };
223- struct SizeVisitor : public boost ::static_visitor<uint16_t >
224- {
225- template <typename T>
226- uint16_t operator ()(T& d) const
227- {
228- return sizeof (d);
229- }
230- };
231- struct SerializeVisitor : public boost ::static_visitor<size_t >
232- {
233- template <typename T>
234- size_t operator ()(T& d, uint8_t * buffer) const
235- {
236- return comm::PackageSerializer::serialize (buffer, d);
237- }
238- };
239202};
240203
241204} // namespace rtde_interface
0 commit comments