Skip to content

Commit

Permalink
pyrosmsg
Browse files Browse the repository at this point in the history
  • Loading branch information
dimatura committed Mar 5, 2018
1 parent 9852545 commit 03e81fb
Show file tree
Hide file tree
Showing 10 changed files with 129 additions and 89 deletions.
27 changes: 8 additions & 19 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,13 +1,13 @@
cmake_minimum_required(VERSION 2.8.3)
project(pymsg)
project(pyrosmsg)

set(CMAKE_CXX_FLAGS "-std=c++11 ${CMAKE_CXX_FLAGS}")

find_package(catkin REQUIRED COMPONENTS
cmake_modules
geometry_msgs
nav_msgs
pybind11_module
pybind11_catkin
roscpp
rospy
sensor_msgs
Expand All @@ -16,10 +16,7 @@ find_package(catkin REQUIRED COMPONENTS
)

find_package(NUMPY REQUIRED)
find_package(Eigen3 3.3.1 REQUIRED)

set(PY_PROJECT_NAME ${PROJECT_NAME})
set(PY_PACKAGE_DIR python/${PROJECT_NAME})
find_package(pybind11 REQUIRED)

catkin_python_setup()

Expand All @@ -30,30 +27,22 @@ catkin_package(
cmake_modules
geometry_msgs
nav_msgs
pybind11_module
pybind11_catkin
roscpp
rospy
sensor_msgs
std_msgs
visualization_msgs
# DEPENDS system_lib
#DEPENDS system_lib
)

###########
## Build ##
###########


include_directories(
include
${Eigen3_INCLUDE_DIR}
${catkin_INCLUDE_DIRS}
#${PYBIND11_INCLUDE_DIRS}
)

add_python_export_library(${PY_PROJECT_NAME} ${PY_PACKAGE_DIR}
message("pybind11_include_dir " ${PYBIND11_INCLUDE_DIRS})
pybind_add_module(libpyrosmsg
src_wrap/module.cpp
)

target_link_libraries(${PY_PROJECT_NAME}
${catkin_LIBRARIES}
)
29 changes: 14 additions & 15 deletions include/pymsg/converters.hpp → include/pyrosmsg/converters.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,9 @@ template <> struct type_caster<std_msgs::Header> {
object msg = MsgType();
msg.attr("seq") = pybind11::cast(header.seq);
msg.attr("stamp") = pybind11::cast(header.stamp);
msg.attr("frame_id") = pybind11::cast(header.frame_id);
// avoid !!python/unicode problem.
//msg.attr("frame_id") = pybind11::cast(header.frame_id);
msg.attr("frame_id") = pybind11::bytes(reinterpret_cast<const char *>(&header.frame_id[0]), header.frame_id.size());
msg.inc_ref();
return msg;
}
Expand Down Expand Up @@ -196,7 +198,8 @@ template <> struct type_caster<geometry_msgs::TransformStamped> {
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::cast(cpp_msg.child_frame_id);
msg.attr("child_frame_id") = pybind11::bytes(reinterpret_cast<const char *>(&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;
Expand All @@ -219,7 +222,10 @@ template <> struct type_caster<sensor_msgs::PointField> {
object mod = module::import("sensor_msgs.msg._PointField");
object MsgType = mod.attr("PointField");
object msg = MsgType();
msg.attr("name") = pybind11::cast(cpp_msg.name);
// avoid !!python/unicode problem.
//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<const char*>(&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);
Expand Down Expand Up @@ -268,11 +274,9 @@ template <> struct type_caster<sensor_msgs::PointCloud2> {
msg.attr("is_bigendian") = pybind11::cast(cpp_msg.is_bigendian);
msg.attr("point_step") = pybind11::cast(cpp_msg.point_step);
msg.attr("row_step") = pybind11::cast(cpp_msg.row_step);
std::string data_str(cpp_msg.data.begin(), cpp_msg.data.end());
pybind11::bytes data_str2(data_str);
msg.attr("data") = data_str2;
//msg.attr("data") = pybind11::bytes(std::string(cpp_msg.data.begin(), cpp_msg.data.end()));
msg.attr("data") = pybind11::bytes(reinterpret_cast<const char *>(&cpp_msg.data[0]), cpp_msg.data.size());
msg.attr("is_dense") = pybind11::cast(cpp_msg.is_dense);

msg.inc_ref();
return msg;
}
Expand All @@ -289,9 +293,7 @@ template <> struct type_caster<sensor_msgs::Image> {
value.encoding = src.attr("encoding").cast<std::string>();
value.is_bigendian = src.attr("is_bigendian").cast<int>();
value.step = src.attr("step").cast<uint32_t>();

std::string data_str = src.attr("data").cast<std::string>();
//value.data = std::vector<uint8_t>(data_str.c_str(), data_str.c_str()+data_str.length());
value.data.insert(value.data.end(), data_str.c_str(), data_str.c_str()+data_str.length());
return true;
}
Expand All @@ -306,12 +308,8 @@ template <> struct type_caster<sensor_msgs::Image> {
msg.attr("encoding") = pybind11::bytes(cpp_msg.encoding);
msg.attr("is_bigendian") = pybind11::cast(cpp_msg.is_bigendian);
msg.attr("step") = pybind11::cast(cpp_msg.step);

// TODO not sure if this works
pybind11::bytes data_str(reinterpret_cast<const char *>(&cpp_msg.data[0]), cpp_msg.data.size());
//std::string data_str(img.data.begin(), img.data.end());
msg.attr("data") = data_str;

//msg.attr("data") = pybind11::bytes(std::string(cpp_msg.data.begin(), cpp_msg.data.end()));
msg.attr("data") = pybind11::bytes(reinterpret_cast<const char *>(&cpp_msg.data[0]), cpp_msg.data.size());
msg.inc_ref();
return msg;
}
Expand Down Expand Up @@ -363,6 +361,7 @@ template <> struct type_caster<sensor_msgs::CameraInfo> {
object mod = module::import("sensor_msgs.msg._CameraInfo");
object MsgType = mod.attr("CameraInfo");
object msg = MsgType();

msg.inc_ref();
return msg;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@

#include <ros/ros.h>

namespace ca { namespace pymsg {
namespace pyrosmsg {

// in python
// buf = StringIO.StringIO()
Expand All @@ -30,8 +30,8 @@ namespace ca { namespace pymsg {
template <class MsgT>
std::string serialize(const MsgT& msg) {
uint32_t serial_size = ros::serialization::serializationLength(msg);
// in practice we could directly use a string.c_str() but that is living dangerously
//boost::shared_array<uint8_t> obuffer(new uint8_t[serial_size]);
// we could directly use a string.c_str(), but not sure if
// that could have ownership issues
uint8_t* obuffer = new uint8_t[serial_size];
ros::serialization::OStream os(obuffer, serial_size);
ros::serialization::serialize(os, msg);
Expand All @@ -51,6 +51,6 @@ void deserialize(const std::string s, MsgT& msg) {
delete[] ibuffer;
}

} }
}

#endif /* end of include guard: SERIALIZATION_H_QC30JWRG */
7 changes: 4 additions & 3 deletions package.xml
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
<?xml version="1.0"?>
<package format="2">
<name>pymsg</name>
<name>pyrosmsg</name>
<version>0.0.0</version>
<description>The pymsg package</description>
<description>The pyrosmsg package</description>

<maintainer email="[email protected]">dmaturan</maintainer>

Expand All @@ -12,7 +12,8 @@

<depend>geometry_msgs</depend>
<depend>nav_msgs</depend>
<depend>pybind11_module</depend>
<!--<depend>pybind11_module</depend>-->
<depend>pybind11_catkin</depend>
<depend>roscpp</depend>
<depend>rospy</depend>
<depend>sensor_msgs</depend>
Expand Down
2 changes: 1 addition & 1 deletion python/pymsg/__init__.py → python/pyrosmsg/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,4 +8,4 @@
#
# @=

from libpymsg import *
from libpyrosmsg import *
20 changes: 10 additions & 10 deletions scratch/sanity.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,22 +8,22 @@

import cv_bridge

import pymsg
import pyrosmsg
import pypcd

#ts = pymsg.make_time()
#ts = pyrosmsg.make_time()
#print ts
#
#tsp = rospy.Time()
#pymsg.print_time(tsp)
#pyrosmsg.print_time(tsp)
#
#hdr = pymsg.make_header(32)
#hdr = pyrosmsg.make_header(32)
#print hdr
#
#pymsg.print_header_seq(hdr)
#pyrosmsg.print_header_seq(hdr)
#
#print
#cloud = pymsg.make_pc2(32)
#cloud = pyrosmsg.make_pc2(32)
#print cloud
#
#print
Expand All @@ -36,15 +36,15 @@

print 'pc_msg.width:', pc_msg.width

pymsg.print_centroid(pc_msg)
pyrosmsg.print_centroid(pc_msg)
print pc_data.mean(0)

#
#print 'ci'
#
#ci = CameraInfo()
#print ci
#pymsg.print_cam_info(ci)
#pyrosmsg.print_cam_info(ci)
#
#print 'img'
#print
Expand All @@ -55,9 +55,9 @@
#img_msg = bridge.cv2_to_imgmsg(cv_img, encoding='passthrough')
#print img_msg
#print '---'
#pymsg.print_img(img_msg)
#pyrosmsg.print_img(img_msg)
#
#print '***'
#img_msg2 = pymsg.make_img(8, 8)
#img_msg2 = pyrosmsg.make_img(8, 8)
#print img_msg2
#cv_img2 = bridge.imgmsg_to_cv2(img_msg2, desired_encoding='passthrough')
7 changes: 3 additions & 4 deletions scratch/serialization.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@

import cStringIO as StringIO
import numpy as np
from pymsg import libpymsg

from sensor_msgs.msg import PointCloud2

Expand All @@ -10,7 +9,7 @@

import pypcd

import pymsg.libpymsg
import pyrosmsg

pc = pypcd.PointCloud.from_path('./tmp.pcd')
msg = pc.to_msg()
Expand All @@ -20,11 +19,11 @@

def with_caster(m):
# 38.4 us per loop,
pymsg.libpymsg.print_centroid(m)
pyrosmsg.print_centroid(m)

def with_serial(m):
# 117 us
buf = StringIO.StringIO()
m.serialize(buf)
smsg = buf.getvalue()
pymsg.libpymsg.print_centroid2(smsg)
pyrosmsg.print_centroid2(smsg)
15 changes: 15 additions & 0 deletions scratch/unicheck.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@

import copy
import numpy as np
import rospy
from std_msgs.msg import Header
from sensor_msgs.msg import CameraInfo
from sensor_msgs.msg import Image

import cv_bridge

import pymsg

hdr = pyrosmsg.make_header(32, "header")
print hdr

3 changes: 1 addition & 2 deletions setup.py
Original file line number Diff line number Diff line change
@@ -1,12 +1,11 @@

## ! DO NOT MANUALLY INVOKE THIS setup.py, USE CATKIN INSTEAD

from distutils.core import setup
from catkin_pkg.python_setup import generate_distutils_setup

# fetch values from package.xml
setup_args = generate_distutils_setup(
packages=['pymsg'],
packages=['pyrosmsg'],
package_dir={'':'python'})

setup(**setup_args)
Loading

0 comments on commit 03e81fb

Please sign in to comment.