It seems that python dynamic_reconfigure does not handle double parameters properly if the min/max values are not specified. In this case, the values are set to the default std::numeric_limits<double>::infinity() which is not understood by python. In the callback, the values are aways set to std::numeric_limits<double>::infinity() instead of the actual parameter. This even causes the rqt_reconfigure gui to crash with the following error:
ValueError: could not convert string to float: -std::numeric_limits<double>::infinity()
Reproduce
The error can be easily reproduced even with the test.cfg in this repository with the following code:
#!/usr/bin/env python
import sys
import rospy
from dynamic_reconfigure.cfg import TestConfig
from dynamic_reconfigure.server import Server
def reconfigure_callback(config, level):
rospy.loginfo("Group2_double value: {}".format(config['group2_double']))
return config
def main(args):
rospy.init_node('issue_node')
reconfigure = Server(TestConfig, reconfigure_callback)
rospy.spin()
if __name__ == '__main__':
main(sys.argv)
rosrunning this code should output _Group2_double value: -std::numericlimits::infinity() instead of 0, the default parameter. If you start an rqt_reconfigure window and try to configure this node, it will crash.
If I manually replace std::numeric_limits<double>::infinity() by infin the generated TestConfig.py, it works.
It seems that python dynamic_reconfigure does not handle double parameters properly if the min/max values are not specified. In this case, the values are set to the default
std::numeric_limits<double>::infinity()
which is not understood by python. In the callback, the values are aways set tostd::numeric_limits<double>::infinity()
instead of the actual parameter. This even causes the rqt_reconfigure gui to crash with the following error:Reproduce
The error can be easily reproduced even with the test.cfg in this repository with the following code:
rosrunning this code should output _Group2_double value: -std::numericlimits::infinity() instead of 0, the default parameter. If you start an rqt_reconfigure window and try to configure this node, it will crash.
If I manually replace
std::numeric_limits<double>::infinity()
byinf
in the generated TestConfig.py, it works.