36 THIS_PACKAGE =
"rosserial_embeddedlinux" 39 make_libraries.py generates the rosserial library files. It 40 requires the location of your project folder. 42 rosrun rosserial_embeddedlinux make_libraries.py <output_path> 46 import rosserial_client
52 ROS_TO_EMBEDDED_TYPES = {
53 'bool' : (
'bool', 1, PrimitiveDataType, []),
54 'byte' : (
'int8_t', 1, PrimitiveDataType, []),
55 'int8' : (
'int8_t', 1, PrimitiveDataType, []),
56 'char' : (
'uint8_t', 1, PrimitiveDataType, []),
57 'uint8' : (
'uint8_t', 1, PrimitiveDataType, []),
58 'int16' : (
'int16_t', 2, PrimitiveDataType, []),
59 'uint16' : (
'uint16_t', 2, PrimitiveDataType, []),
60 'int32' : (
'int32_t', 4, PrimitiveDataType, []),
61 'uint32' : (
'uint32_t', 4, PrimitiveDataType, []),
62 'int64' : (
'int64_t', 8, PrimitiveDataType, []),
63 'uint64' : (
'uint64_t', 4, PrimitiveDataType, []),
64 'float32' : (
'float', 4, PrimitiveDataType, []),
65 'float64' : (
'double', 8, PrimitiveDataType, []),
66 'time' : (
'ros::Time', 8, TimeDataType, [
'ros/time']),
67 'duration': (
'ros::Duration', 8, TimeDataType, [
'ros/duration']),
68 'string' : (
'char*', 0, StringDataType, []),
69 'Header' : (
'std_msgs::Header', 0, MessageDataType, [
'std_msgs/Header'])
73 if (len(sys.argv) < 2):
81 print "\nExporting to %s" % path
83 rospack = rospkg.RosPack()
86 rosserial_arduino_dir = rospack.get_path(THIS_PACKAGE)
87 shutil.copytree(rosserial_arduino_dir+
"/src/ros_lib", path+
"/ros_lib")
88 rosserial_client_copy_files(rospack, path+
"/ros_lib/")
89 shutil.copytree(rosserial_arduino_dir+
"/src/examples", path+
"/examples")
92 rosserial_generate(rospack, path+
"/ros_lib", ROS_TO_EMBEDDED_TYPES)