make_libraries.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 
35 
36 THIS_PACKAGE = "rosserial_embeddedlinux"
37 
38 __usage__ = """
39 make_libraries.py generates the rosserial library files. It
40 requires the location of your project folder.
41 
42 rosrun rosserial_embeddedlinux make_libraries.py <output_path>
43 """
44 
45 import rospkg
46 import rosserial_client
48 
49 # for copying files
50 import shutil
51 import os.path
52 
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'])
71 }
72 
73 # need correct inputs
74 if (len(sys.argv) < 2):
75  print(__usage__)
76  exit()
77 
78 # get output path
79 path = sys.argv[1]
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))
83 
84 rospack = rospkg.RosPack()
85 
86 # copy ros_lib stuff in
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)
91 
92 # generate messages
93 rosserial_generate(rospack, output_path, ROS_TO_EMBEDDED_TYPES)
rosserial_client::make_library


rosserial_embeddedlinux
Author(s): Paul Bouchier
autogenerated on Wed Mar 2 2022 00:58:06