diff --git a/CMakeLists.txt b/CMakeLists.txt index f594248..b6af5c4 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -7,7 +7,6 @@ find_package(catkin REQUIRED COMPONENTS cmake_modules geometry_msgs nav_msgs - pybind11 pybind11_catkin roscpp rospy diff --git a/include/pyrosmsg/converters.hpp b/include/pyrosmsg/converters.hpp index 762e459..529cbaa 100644 --- a/include/pyrosmsg/converters.hpp +++ b/include/pyrosmsg/converters.hpp @@ -1,5 +1,4 @@ -#ifndef CONVERTERS_H_L7OWNAZ8 -#define CONVERTERS_H_L7OWNAZ8 +#pragma once // TODO // should break this up by package, @@ -101,10 +100,10 @@ struct type_caster { msg.attr("seq") = pybind11::cast(header.seq); msg.attr("stamp") = pybind11::cast(header.stamp); // avoid !!python/unicode problem. - // msg.attr("frame_id") = pybind11::cast(header.frame_id); - msg.attr("frame_id") = - pybind11::bytes(reinterpret_cast(&header.frame_id[0]), - header.frame_id.size()); + msg.attr("frame_id") = pybind11::cast(header.frame_id); + // msg.attr("frame_id") = + // pybind11::bytes(reinterpret_cast(&header.frame_id[0]), + // header.frame_id.size()); msg.inc_ref(); return msg; } @@ -247,10 +246,10 @@ struct type_caster { object MsgType = mod.attr("TransformStamped"); object msg = MsgType(); msg.attr("header") = pybind11::cast(cpp_msg.header); - // msg.attr("child_frame_id") = pybind11::cast(cpp_msg.child_frame_id); - msg.attr("child_frame_id") = pybind11::bytes( - reinterpret_cast(&cpp_msg.child_frame_id[0]), - cpp_msg.child_frame_id.size()); + msg.attr("child_frame_id") = pybind11::cast(cpp_msg.child_frame_id); + // msg.attr("child_frame_id") = pybind11::bytes( + // reinterpret_cast(&cpp_msg.child_frame_id[0]), + // cpp_msg.child_frame_id.size()); msg.attr("transform") = pybind11::cast(cpp_msg.transform); msg.inc_ref(); return msg; @@ -279,10 +278,10 @@ struct type_caster { object MsgType = mod.attr("PointField"); object msg = MsgType(); // avoid !!python/unicode problem. - // msg.attr("name") = pybind11::cast(cpp_msg.name); + msg.attr("name") = pybind11::cast(cpp_msg.name); // msg.attr("name") = PyString_FromString(cpp_msg.name.c_str()); - msg.attr("name") = pybind11::bytes( - reinterpret_cast(&cpp_msg.name[0]), cpp_msg.name.size()); + // msg.attr("name") = pybind11::bytes( + // reinterpret_cast(&cpp_msg.name[0]), cpp_msg.name.size()); msg.attr("offset") = pybind11::cast(cpp_msg.offset); msg.attr("datatype") = pybind11::cast(cpp_msg.datatype); msg.attr("count") = pybind11::cast(cpp_msg.count); @@ -503,7 +502,5 @@ struct type_caster { return msg; } }; -} -} +}} -#endif /* end of include guard: CONVERTERS_H_L7OWNAZ8 */