Skip to content

Commit 23824b0

Browse files
committed
- Removed the need for _extra in eye_asset/name. Introduced asset_param_list.py to provide a list of parameters, since rosserial_client does not support param_list.
- Added support for iris_zoom (controls iris and pupil reflex), upperlid_zoom, and extra_zoom.
1 parent c936971 commit 23824b0

File tree

1 file changed

+59
-0
lines changed

1 file changed

+59
-0
lines changed
Lines changed: 59 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,59 @@
1+
#!/usr/bin/env python
2+
3+
import os
4+
import rospy
5+
import rosparam
6+
from rosserial_msgs.srv import RequestParam, RequestParamResponse
7+
8+
# This node provides a list of parameters related to eye_asset.
9+
# When getParam is called from the ESP32 with non-existent names, it takes a long time to timeout and returns an error.
10+
# To prevent this delay, we first retrieve the list of available parameter names before requesting their values.
11+
12+
def main():
13+
rospy.init_node('asset_param_list')
14+
15+
# get eye_asset param
16+
param_ns = rospy.get_namespace().rstrip('/')
17+
eye_asset_names = rospy.get_param("{}/eye_asset/names".format(param_ns))
18+
19+
for name in eye_asset_names:
20+
eye_asset_param_names = rospy.get_param("{}/eye_asset/{}".format(param_ns, name)).keys()
21+
22+
eye_types = []
23+
for key in eye_asset_param_names:
24+
# image path : cehck if key start with path_
25+
if key.startswith("path_"):
26+
eye_type = key[len("path_"):]
27+
eye_types.append(eye_type)
28+
rospy.set_param("{}/eye_asset_{}_eye_types".format(param_ns, name), eye_types)
29+
30+
positions = []
31+
for eye_type in eye_types:
32+
positions.extend([n for n in eye_asset_param_names if n.startswith("{}_position".format(eye_type))])
33+
if not positions:
34+
positions.append('NONE')
35+
rospy.set_param("{}/eye_asset_{}_positions".format(param_ns, name), positions)
36+
37+
rotations = []
38+
for eye_type in eye_types:
39+
rotations.extend([n for n in eye_asset_param_names if n.startswith("{}_rotation".format(eye_type))])
40+
if not rotations:
41+
rotations.append('NONE')
42+
rospy.set_param("{}/eye_asset_{}_rotations".format(param_ns, name), rotations)
43+
44+
defaults = []
45+
for eye_type in eye_types:
46+
defaults.extend([n for n in eye_asset_param_names if n.startswith("{}_default".format(eye_type))])
47+
if not defaults:
48+
defaults.append('NONE')
49+
rospy.set_param("{}/eye_asset_{}_defaults".format(param_ns, name), defaults)
50+
51+
zooms = []
52+
for eye_type in eye_types:
53+
zooms.extend([n for n in eye_asset_param_names if n.startswith("{}_zoom".format(eye_type))])
54+
if not zooms:
55+
zooms.append('NONE')
56+
rospy.set_param("{}/eye_asset_{}_zooms".format(param_ns, name), zooms)
57+
58+
if __name__ == "__main__":
59+
main()

0 commit comments

Comments
 (0)