Skip to content

Commit d8d0d4d

Browse files
committed
Fixes in services in database_server
1 parent 92b4c64 commit d8d0d4d

File tree

3 files changed

+40
-34
lines changed

3 files changed

+40
-34
lines changed

mocha_core/mocha_core/database_server.py

Lines changed: 21 additions & 25 deletions
Original file line numberDiff line numberDiff line change
@@ -67,86 +67,82 @@ def __init__(self, robot_configs, topic_configs, robot_name, node=None):
6767

6868
self.msg_types = du.msg_types(self.robot_configs, self.topic_configs)
6969

70-
def add_update_db_service_cb(self, req):
70+
def add_update_db_service_cb(self, request, response):
7171
try:
72-
if not isinstance(req.topic_id, int) or req.topic_id is None:
72+
if not isinstance(request.topic_id, int) or request.topic_id is None:
7373
self.logger.error("topic_id empty")
74-
return mocha_core.srv.AddUpdateDB.Response()
75-
if len(req.msg_content) == 0:
74+
return response
75+
if len(request.msg_content) == 0:
7676
self.logger.error("msg_content empty")
77-
return mocha_core.srv.AddUpdateDB.Response()
78-
if req.topic_id >= len(self.topic_list): # Changed > to >= for proper bounds check
79-
self.logger.error(f"topic_id {req.topic_id} not in topic_list (length: {len(self.topic_list)})")
80-
return mocha_core.srv.AddUpdateDB.Response()
77+
return response
78+
if request.topic_id >= len(self.topic_list): # Changed > to >= for proper bounds check
79+
self.logger.error(f"topic_id {request.topic_id} not in topic_list (length: {len(self.topic_list)})")
80+
return response
8181

82-
topic = self.topic_list[req.topic_id]
82+
topic = self.topic_list[request.topic_id]
8383
priority = du.get_priority_number(topic["msg_priority"])
84-
ts = req.timestamp
84+
ts = request.timestamp
8585
# ROS2 builtin_interfaces/Time uses 'sec' and 'nanosec' fields
8686
ts = rclpy.time.Time(seconds=ts.sec, nanoseconds=ts.nanosec)
8787

8888
# Convert array to bytes if needed (ROS2 service messages use array)
89-
msg_data = req.msg_content
89+
msg_data = request.msg_content
9090
if hasattr(msg_data, 'tobytes'):
9191
msg_data = msg_data.tobytes()
9292
elif isinstance(msg_data, (list, tuple)):
9393
msg_data = bytes(msg_data)
9494

9595
dbm = database.DBMessage(self.robot_number,
96-
req.topic_id,
97-
dtype=self.msg_types[self.robot_number][req.topic_id]["dtype"],
96+
request.topic_id,
97+
dtype=self.msg_types[self.robot_number][request.topic_id]["dtype"],
9898
priority=priority,
9999
ts=ts,
100100
data=msg_data)
101101

102102
header = self.dbl.add_modify_data(dbm)
103-
response = mocha_core.srv.AddUpdateDB.Response()
104103
response.new_header = header
105104
return response
106105
except Exception as e:
107106
self.logger.error(f"Exception in add_update_db_service_cb: {e}")
108-
return mocha_core.srv.AddUpdateDB.Response()
107+
return response
109108

110-
def get_data_hash_db_service_cb(self, req):
109+
def get_data_hash_db_service_cb(self, request, response):
111110
try:
112-
if req.msg_header is None or len(req.msg_header) == 0:
111+
if request.msg_header is None or len(request.msg_header) == 0:
113112
self.logger.error("msg_header empty")
114-
return mocha_core.srv.GetDataHeaderDB.Response()
113+
return response
115114

116115
# Convert array to bytes if needed (ROS2 service messages use array)
117-
header_data = req.msg_header
116+
header_data = request.msg_header
118117
if hasattr(header_data, 'tobytes'):
119118
header_data = header_data.tobytes()
120119
elif isinstance(header_data, (list, tuple)):
121120
header_data = bytes(header_data)
122121

123122
dbm = self.dbl.find_header(header_data)
124123

125-
response = mocha_core.srv.GetDataHeaderDB.Response()
126124
response.robot_id = dbm.robot_id
127125
response.topic_id = dbm.topic_id
128126
response.timestamp = dbm.ts
129127
response.msg_content = dbm.data
130128
return response
131129
except Exception as e:
132130
self.logger.error(f"Exception in get_data_hash_db_service_cb: {e}")
133-
return mocha_core.srv.GetDataHeaderDB.Response()
131+
return response
134132

135-
def select_db_service_cb(self, req):
133+
def select_db_service_cb(self, request, response):
136134
try:
137135
# TODO Implement filtering
138-
response = mocha_core.srv.SelectDB.Response()
139136

140137
# Note: robot_id and topic_id are uint8 in ROS2, so they can't be None
141138
# We can add range validation if needed, but for now just proceed
142139

143-
list_headers = self.dbl.get_header_list(req.robot_id)
140+
list_headers = self.dbl.get_header_list(request.robot_id)
144141

145142
response.headers = du.serialize_headers(list_headers)
146143
return response
147144
except Exception as e:
148145
self.logger.error(f"Exception in select_db_service_cb: {e}")
149-
response = mocha_core.srv.SelectDB.Response()
150146
response.headers = b''
151147
return response
152148

mocha_core/mocha_core/integrate_database.py

Lines changed: 7 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -163,8 +163,9 @@ def shutdown(self, reason):
163163
channel.comm_node.terminate()
164164
self.all_channels.remove(channel)
165165
self.logger.warning(f"{self.this_robot} - Integrate - " + "Killed Channels")
166-
self.DBServer.shutdown()
167-
self.logger.warning(f"{self.this_robot} - Integrate - " + "Killed DB")
166+
if hasattr(self, 'DBServer') and self.DBServer is not None:
167+
self.DBServer.shutdown()
168+
self.logger.warning(f"{self.this_robot} - Integrate - " + "Killed DB")
168169
if rclpy.ok():
169170
rclpy.shutdown()
170171
self.logger.warning(f"{self.this_robot} - Integrate - " + "Shutting down")
@@ -180,6 +181,9 @@ def rssi_cb(self, data, comm_node):
180181
traceback.print_exception(*sys.exc_info())
181182

182183

183-
if __name__ == "__main__":
184+
def main():
184185
# Start the node
185186
IntegrateDatabase()
187+
188+
if __name__ == "__main__":
189+
main()

mocha_core/test/test_database_server.py

Lines changed: 12 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -74,7 +74,8 @@ def test_add_retrieve_single_msg(self):
7474
req.topic_id = tid
7575
req.timestamp = rclpy.clock.Clock().now().to_msg()
7676
req.msg_content = serialized_msg
77-
answ = self.dbs.add_update_db_service_cb(req)
77+
response = mocha_core.srv.AddUpdateDB.Response()
78+
answ = self.dbs.add_update_db_service_cb(req, response)
7879
answ_header = answ.new_header
7980
except Exception as exc:
8081
print("Service did not process request: " + str(exc))
@@ -87,7 +88,8 @@ def test_add_retrieve_single_msg(self):
8788
# Create request and call service method directly
8889
req = mocha_core.srv.GetDataHeaderDB.Request()
8990
req.msg_header = answ_header
90-
answ = self.dbs.get_data_hash_db_service_cb(req)
91+
response = mocha_core.srv.GetDataHeaderDB.Response()
92+
answ = self.dbs.get_data_hash_db_service_cb(req, response)
9193
except Exception as exc:
9294
print("Service did not process request: " + str(exc))
9395
self.assertTrue(False)
@@ -125,7 +127,8 @@ def test_add_select_robot(self):
125127
req.topic_id = tid
126128
req.timestamp = rclpy.clock.Clock().now().to_msg()
127129
req.msg_content = serialized_msg
128-
answ = self.dbs.add_update_db_service_cb(req)
130+
response = mocha_core.srv.AddUpdateDB.Response()
131+
answ = self.dbs.add_update_db_service_cb(req, response)
129132
answ_header = answ.new_header
130133
except Exception as exc:
131134
print("Service did not process request: " + str(exc))
@@ -140,7 +143,8 @@ def test_add_select_robot(self):
140143
req.robot_id = robot_id
141144
req.topic_id = 0 # Changed from None to 0 since it's uint8
142145
req.ts_limit = rclpy.clock.Clock().now().to_msg()
143-
answ = self.dbs.select_db_service_cb(req)
146+
response = mocha_core.srv.SelectDB.Response()
147+
answ = self.dbs.select_db_service_cb(req, response)
144148
except Exception as exc:
145149
print("Service did not process request: " + str(exc))
146150
self.assertTrue(False)
@@ -185,7 +189,8 @@ def recorder_thread():
185189
req.topic_id = tid
186190
req.timestamp = timestamp
187191
req.msg_content = serialized_msg
188-
_ = self.dbs.add_update_db_service_cb(req)
192+
response = mocha_core.srv.AddUpdateDB.Response()
193+
_ = self.dbs.add_update_db_service_cb(req, response)
189194
except Exception as exc:
190195
print(f"Service did not process request: {exc}")
191196

@@ -209,7 +214,8 @@ def recorder_thread():
209214
req.robot_id = robot_id
210215
req.topic_id = 0 # Changed from None to 0 since it's uint8
211216
req.ts_limit = rclpy.clock.Clock().now().to_msg()
212-
answ = self.dbs.select_db_service_cb(req)
217+
response = mocha_core.srv.SelectDB.Response()
218+
answ = self.dbs.select_db_service_cb(req, response)
213219
except Exception as exc:
214220
print("Service did not process request: " + str(exc))
215221
self.assertTrue(False)

0 commit comments

Comments
 (0)