Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fixed issue occuring during alternating calls of getParamCached and setParam #1439

Merged
merged 10 commits into from
Apr 1, 2019
15 changes: 13 additions & 2 deletions test/test_roscpp/test/src/params.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -566,12 +566,23 @@ TEST(Params, getParamNames) {
EXPECT_LT(10u, test_params.size());
}

TEST(Params, getParamCachedSetParamLoop) {
NodeHandle nh;
const std::string name = "changeable_int";
for (int i = 0; i < 100; i++) {
nh.setParam(name, i);
int v = 0;
ASSERT_TRUE(nh.getParamCached(name, v));
ASSERT_EQ(i, v);
}
}

int
main(int argc, char** argv)
{
testing::InitGoogleTest(&argc, argv);
ros::init( argc, argv, "params" );
// ros::NodeHandle nh;
ros::init(argc, argv, "params");
ros::NodeHandle nh;

return RUN_ALL_TESTS();
}
2 changes: 1 addition & 1 deletion test/test_rospy/test/rostest/sub_to_multiple_pubs.test
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
<launch>
<node name="listener" pkg="test_rospy" type="listener.py" />
<node name="talker1" pkg="test_rospy" type="talker.py" />
<node name="talker2" pkg="test_rospy" type="talker.py" />
<node name="talker3" pkg="test_rospy" type="talker.py" />
Expand Down Expand Up @@ -98,6 +99,5 @@
<node name="talker97" pkg="test_rospy" type="talker.py" />
<node name="talker98" pkg="test_rospy" type="talker.py" />
<node name="talker99" pkg="test_rospy" type="talker.py" />
<node name="listener" pkg="test_rospy" type="listener.py" />
<test test-name="sub_to_multiple_pubs" pkg="test_rospy" type="test_sub_to_multiple_pubs.py" />
</launch>
2 changes: 1 addition & 1 deletion tools/rosmaster/src/rosmaster/master_api.py
Original file line number Diff line number Diff line change
Expand Up @@ -375,7 +375,7 @@ def setParam(self, caller_id, key, value):
@rtype: [int, str, int]
"""
key = resolve_name(key, caller_id)
self.param_server.set_param(key, value, self._notify_param_subscribers)
self.param_server.set_param(key, value, self._notify_param_subscribers, caller_id)
mloginfo("+PARAM [%s] by %s",key, caller_id)
return 1, "parameter %s set"%key, 0

Expand Down
15 changes: 12 additions & 3 deletions tools/rosmaster/src/rosmaster/paramserver.py
Original file line number Diff line number Diff line change
Expand Up @@ -166,7 +166,7 @@ def get_param(self, key):
finally:
self.lock.release()

def set_param(self, key, value, notify_task=None):
def set_param(self, key, value, notify_task=None, caller_id=None):
"""
Set the parameter in the parameter dictionary.

Expand All @@ -178,6 +178,8 @@ def set_param(self, key, value, notify_task=None):
[(subscribers, param_key, param_value)*]. The empty dictionary
represents an unset parameter.
@type notify_task: fn(updates)
@param caller_id: the caller id
@type caller_id: str
"""
try:
self.lock.acquire()
Expand Down Expand Up @@ -208,7 +210,7 @@ def set_param(self, key, value, notify_task=None):

# ParamDictionary needs to queue updates so that the updates are thread-safe
if notify_task:
updates = compute_param_updates(self.reg_manager.param_subscribers, key, value)
updates = compute_param_updates(self.reg_manager.param_subscribers, key, value, caller_id)
if updates:
notify_task(updates)
finally:
Expand Down Expand Up @@ -332,7 +334,7 @@ def _compute_all_keys(param_key, param_value, all_keys=None):
_compute_all_keys(new_k, v, all_keys)
return all_keys

def compute_param_updates(subscribers, param_key, param_value):
def compute_param_updates(subscribers, param_key, param_value, caller_id_to_ignore=None):
"""
Compute subscribers that should be notified based on the parameter update
@param subscribers: parameter subscribers
Expand All @@ -341,6 +343,8 @@ def compute_param_updates(subscribers, param_key, param_value):
@type param_key: str
@param param_value: parameter value
@type param_value: str
@param caller_id_to_ignore: the caller to ignore
@type caller_id_to_ignore: str
"""

# logic correct for both updates and deletions
Expand Down Expand Up @@ -368,6 +372,11 @@ def compute_param_updates(subscribers, param_key, param_value):
ns_key = sub_key + SEP
if param_key.startswith(ns_key):
node_apis = subscribers[sub_key]
if caller_id_to_ignore is not None:
node_apis = [
(caller_id, caller_api)
for (caller_id, caller_api) in node_apis
if caller_id != caller_id_to_ignore]
updates.append((node_apis, param_key, param_value))
elif all_keys is not None and ns_key.startswith(param_key) \
and not sub_key in all_keys:
Expand Down