exposing c++ API through Boost.Python and common_msgs [closed]

asked 2012-06-01 06:03:10 -0500

updated 2014-01-28 17:12:32 -0500

ngrennan gravatar image

I'm bulding a library in C++ which offer a set of classes and functions. I wanted to export this functionality through the boost.python library mechanism.

All went well until I tested the code in python. It was not possible using common msgs in python as arguments of such functions because they are not considered the same type.


import roslib
roslib.load_manifest("rtcus_motion_models")
import rospy
from geometry_msgs.msg import *
import libpython_rtcus_motion_models
from libpython_rtcus_motion_models import DeterministicNonHolonomic2D

dt=rospy.Duration(100)
initial_state=Pose()
final_state=Pose()
action=Twist()
action.linear.x=1.0
initial_state.orientation.w=1.0
motion_model=DeterministicNonHolonomic2D()
motion_model.estimateState(initial_state,action,dt,final_state)

---------------------------------------------------------------------------
ArgumentError                             Traceback (most recent call last)
/Datos/Archivos/Tesis/Tesis/Code/rtcus_motion_models/lib/<ipython-input-23-3e92861c2c94> in <module>()
----> 1 motion_model.estimateState(initial_state,action,dt,final_state)

ArgumentError: Python argument types in
    DeterministicNonHolonomic2D.estimateState(DeterministicNonHolonomic2D, Pose, Twist, Duration, Pose)
did not match C++ signature:
    estimateState(rtcus_motion_models::DeterministicNonHolonomic2D<geometry_msgs::pose_<std::allocator<void> >, geometry_msgs::Twist_<std::allocator<void> > > {lvalue}, geometry_msgs::Pose_<std::allocator<void> >, geometry_msgs::Twist_<std::allocator<void> >, ros::Duration, geometry_msgs::Pose_<std::allocator<void> > {lvalue})
 

Are there any implemented mechanism to convert from these "common msgs python data structures" to "boost.python python data structures"?

I'm afraid there are not.

In such case I think it would be possible using the msg IDL to generate cpp code to expose such data structures in a "boost.python way". Then an uniform way of exporting c++ code to python would be available.

I tested my API converting some of the most basic ros msgs and it worked well.


BOOST_PYTHON_MODULE(libpython_rtcus_motion_models)
{
  using namespace rtcus_motion_models;
  using namespace geometry_msgs;
  class_<Point>("Point")
      .def_readwrite("x", &Point::x)
      .def_readwrite("y", &Point::y)
      .def_readwrite("z", &Point::z);

  class_<Vector3>("Vector3")
      .def_readwrite("x", &Vector3::x)
      .def_readwrite("y", &Vector3::y)
      .def_readwrite("z", &Vector3::z);

  class_<Quaternion>("Quaternion")
      .def_readwrite("x", &Quaternion::x)
      .def_readwrite("y", &Quaternion::y)
      .def_readwrite("z", &Quaternion::z)
      .def_readwrite("w", &Quaternion::w);

  class_<Pose>("Pose")
      .def_readwrite("position", &Pose::position)
      .def_readwrite("orientation", &Pose::orientation);

  class_<Twist>("Twist")
      .def_readwrite("linear", &Twist::linear)
      .def_readwrite("angular", &Twist::angular);

  class_<ros::Duration>("Duration",init<int>());

 class_<rtcus_motion_models::DeterministicNonHolonomic2D < Pose, Twist> >("DeterministicNonHolonomic2D").def(
      "estimateState", &DeterministicNonHolonomic2D<Pose, Twist>::estimateState);
}
</pre>
 

Test in python which work well


import libpython_rtcus_motion_models
dt=libpython_rtcus_motion_models.Duration(100)
initial_state=libpython_rtcus_motion_models.Pose()
final_state=libpython_rtcus_motion_models.Pose()
action=libpython_rtcus_motion_models.Twist()
action.linear.x=1.0
initial_state.orientation.w=1.0
motion_model=libpython_rtcus_motion_models.DeterministicNonHolonomic2D()
motion_model.estimateState(initial_state,action,dt,final_state)
final_state.position.x
Out[29]: 100.0
 
edit retag flag offensive reopen merge delete

Closed for the following reason question is not relevant or outdated by tfoote
close date 2015-03-03 01:49:50.350836