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
53 ROS_TO_EMBEDDED_TYPES = {
54 'bool' : (
'bool', 1, PrimitiveDataType, []),
55 'byte' : (
'int8_t', 1, PrimitiveDataType, []),
56 'int8' : (
'int8_t', 1, PrimitiveDataType, []),
57 'char' : (
'uint8_t', 1, PrimitiveDataType, []),
58 'uint8' : (
'uint8_t', 1, PrimitiveDataType, []),
59 'int16' : (
'int16_t', 2, PrimitiveDataType, []),
60 'uint16' : (
'uint16_t', 2, PrimitiveDataType, []),
61 'int32' : (
'int32_t', 4, PrimitiveDataType, []),
62 'uint32' : (
'uint32_t', 4, PrimitiveDataType, []),
63 'int64' : (
'int64_t', 8, PrimitiveDataType, []),
64 'uint64' : (
'uint64_t', 4, PrimitiveDataType, []),
65 'float32' : (
'float', 4, PrimitiveDataType, []),
66 'float64' : (
'double', 8, PrimitiveDataType, []),
67 'time' : (
'ros::Time', 8, TimeDataType, [
'ros/time']),
68 'duration': (
'ros::Duration', 8, TimeDataType, [
'ros/duration']),
69 'string' : (
'char*', 0, StringDataType, []),
70 'Header' : (
'std_msgs::Header', 0, MessageDataType, [
'std_msgs/Header'])
74 if (len(sys.argv) < 2):
80 output_path = os.path.join(sys.argv[1],
"ros_lib")
81 examples_path = os.path.join(sys.argv[1],
"examples")
82 print(
"\nExporting to %s and %s" % (output_path, examples_path))
84 rospack = rospkg.RosPack()
87 shutil.rmtree(output_path, ignore_errors=
True)
88 shutil.copytree(os.path.join(rospack.get_path(THIS_PACKAGE),
"src",
"ros_lib"), output_path)
89 rosserial_client_copy_files(rospack, output_path)
90 shutil.copytree(os.path.join(rospack.get_path(THIS_PACKAGE),
"src",
"examples"), examples_path)
93 rosserial_generate(rospack, output_path, ROS_TO_EMBEDDED_TYPES)