[ros-users] communicating with windows

Klaus Petersen petersen at vftb.com
Tue Jun 15 16:15:11 UTC 2010


Hi Aaron,

I have done both, using the python framework to communicate from windows 
c++ with ros nodes on linux, and checked proprietary solutions. I will 
re-post what I think the easiest way is to communicate in the python way 
below. However, in the end I came to prefer to communicate between 
windows and ros using ice (www.zeroc.com) If you just need to pass some 
data, this is very easy to set up. Check the documentation, they have 
some examples for basic remote message calling for c# as well. Ice has 
of course a different scope than ros and can not substitute its 
functionality (except if you build your own framework around it), but as 
I said for quickly passing data it is excellent.

Klaus


The former post regarding windows / python / vc++ (not c# anyway):

To receive ros standard messages (Float32 in this example) in vc++
(thats what I checked it with) I did something like this:

#undef _DEBUG
#include <Python.h>

// the method that gets embedded into python
static PyObject* ros_indirect_callback(PyObject *self, PyObject *args)
{
	double double_data;

     	if (!PyArg_ParseTuple(args, "d", &double_data))
         	return NULL;

	printf("Do something with the data %f here.\n", double_data);
	
	return Py_BuildValue("i", 0);
}

// some data in order to register the method
static PyMethodDef embedded_methods[] =
{
	{
		"ros_indirect_callback",
		ros_indirect_callback,
		METH_VARARGS,
		""
	},
     	{
		NULL,
		NULL,
		0,
		NULL
	}
};

// thread that runs the ros node (gets locked after calling spin())
void ros_thread::run(void)
{
	Py_Initialize();
	Py_InitModule("ros_win", embedded_methods);	
	
	PySys_SetArgv(0, argv);

	PyRun_SimpleString("import ros_win\n"
		"import roslib\n"
		"import rospy\n"
		"from std_msgs.msg import Float32" );

	PyRun_SimpleString("def callback(data):\n"
		"	ros_win.ros_indirect_callback(data.data)\n" );

	PyRun_SimpleString("rospy.init_node('listener', anonymous=True)\n"
		"rospy.Subscriber('chatter', Float32, callback)\n"
		"rospy.spin()\n" );
}


To send messages:

#undef _DEBUG
#include <Python.h>

#include <string>
#include <boost/lexical_cast.hpp>

using namespace std;

void send_double_data(double v)
{	
	Py_Initialize();	
	PySys_SetArgv(0, argv);

	string s_str = "str = " + boost::lexical_cast<std::string>(v);	
	PyRun_SimpleString(s_str.c_str());
	
	PyRun_SimpleString("rospy.loginfo(str)\n"
		"pub.publish(Float32(str))\n");
}


For reference:
http://www.ros.org/wiki/Windows
http://docs.python.org/extending/index.html
http://www.boost.org/doc/libs/1_42_0/libs/python/doc/index.html


Aaron Solochek さんは書きました:
> Yeah, I've read that.  It addresses getting ROS running on windows,
> which is not what I want to do.  I don't need a complete ROS environment
> on windows.  All I need is to communicate with a ROS network.
> 
> My question is whether it will be fairly straight forward to emulate a a
> very simple ROS node on windows (capable of sending joystick commands),
> or if that will be complicated enough that I'm better off doing
> something proprietary for the windows<->ROS communication link.
> 
> To be clear, I'm talking about trying to implement the bare minimum
> required to appear as a ROS node to roscore (running on another machine)
> from scratch in C#.
> 
> -Aaron
> 
> 
> 
> On 6/14/2010 5:18 PM, Ken Conley wrote:
>> This wiki page has all the currently known ways of getting running on
>> Windows:
>>
>> http://www.ros.org/wiki/Windows
>>
>>  - Ken
>>
>> On Mon, Jun 14, 2010 at 11:18 AM, Aaron Solochek
>> <aarons-ros at aberrant.org <mailto:aarons-ros at aberrant.org>> wrote:
>>
>>     The system I'm working on uses ROS on the backend for a variety of
>>     control stuff, but has a user interface that is going to be written
>>     in C#.
>>
>>     What is the recommended way to get some 2-way communication going
>>     between this windows program and ROS?  Should I make a node on the linux
>>     box that speaks some proprietary thing with the windows program, or
>>     should I try to implement a ROS node in C#?
>>
>>     Better yet, has anyone already done something I can use for this? :)
>>
>>     Any advice would be appreciated, and please copy me on replies since I'm
>>     only getting the daily digest of this list.
>>
>>     Thanks,
>>
>>     -Aaron
>>     _______________________________________________
>>     ros-users mailing list
>>     ros-users at code.ros.org <mailto:ros-users at code.ros.org>
>>     https://code.ros.org/mailman/listinfo/ros-users
>>
>>
>> !DSPAM:4c169cd0309315323969998!
> 
> _______________________________________________
> ros-users mailing list
> ros-users at code.ros.org
> https://code.ros.org/mailman/listinfo/ros-users
> 




More information about the ros-users mailing list