Skip to content

Commit 500bf2f

Browse files
remove trailing whitespaces (#88)
1 parent 80ad8cf commit 500bf2f

18 files changed

+164
-164
lines changed

cmake/dynamic_reconfigure-macros.cmake

+5-5
Original file line numberDiff line numberDiff line change
@@ -13,19 +13,19 @@ macro(generate_dynamic_reconfigure_options)
1313
if(NOT IS_ABSOLUTE ${_input})
1414
set(_input ${PROJECT_SOURCE_DIR}/${_input})
1515
endif()
16-
16+
1717
# The .cfg file is its own generator.
18-
set(gencfg_build_files
18+
set(gencfg_build_files
1919
${dynamic_reconfigure_BASE_DIR}/templates/ConfigType.py.template
2020
${dynamic_reconfigure_BASE_DIR}/templates/ConfigType.h.template
21-
)
21+
)
2222

2323
get_filename_component(_cfgonly ${_cfg} NAME_WE)
2424
set(_output_cpp ${CATKIN_DEVEL_PREFIX}/${CATKIN_PACKAGE_INCLUDE_DESTINATION}/${_cfgonly}Config.h)
2525
set(_output_py ${CATKIN_DEVEL_PREFIX}/${CATKIN_PACKAGE_PYTHON_DESTINATION}/cfg/${_cfgonly}Config.py)
2626
set(_output_dox ${CATKIN_DEVEL_PREFIX}/${CATKIN_PACKAGE_SHARE_DESTINATION}/docs/${_cfgonly}Config.dox)
2727
set(_output_wikidoc ${CATKIN_DEVEL_PREFIX}/${CATKIN_PACKAGE_SHARE_DESTINATION}/docs/${_cfgonly}Config.wikidoc)
28-
set(_output_usage ${CATKIN_DEVEL_PREFIX}/${CATKIN_PACKAGE_SHARE_DESTINATION}/docs/${_cfgonly}Config-usage.dox)
28+
set(_output_usage ${CATKIN_DEVEL_PREFIX}/${CATKIN_PACKAGE_SHARE_DESTINATION}/docs/${_cfgonly}Config-usage.dox)
2929

3030
# we need to explicitly add the devel space to the PYTHONPATH
3131
# since it might contain dynamic_reconfigure or Python code of the current package
@@ -54,7 +54,7 @@ macro(generate_dynamic_reconfigure_options)
5454

5555
add_custom_command(OUTPUT
5656
${_output_cpp} ${_output_dox} ${_output_usage} ${_output_py} ${_output_wikidoc}
57-
COMMAND ${_cmd}
57+
COMMAND ${_cmd}
5858
DEPENDS ${_input} ${gencfg_build_files}
5959
COMMENT "Generating dynamic reconfigure files from ${_cfg}: ${_output_cpp} ${_output_py}"
6060
)

cmake/dynamic_reconfigure/parameter_generator.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,7 @@
3939
class ParameterGenerator():
4040
@staticmethod
4141
def dummy(*params, **nparams):
42-
return
42+
return
4343

4444
def __getattr__(self, name):
4545
return self.dummy

include/dynamic_reconfigure/config_tools.h

+9-9
Original file line numberDiff line numberDiff line change
@@ -16,42 +16,42 @@ class ConfigTools
1616
{
1717
return set.bools;
1818
}
19-
19+
2020
static std::vector<dynamic_reconfigure::IntParameter> &getVectorForType(dynamic_reconfigure::Config &set, const int /*val*/)
2121
{
2222
return set.ints;
2323
}
24-
24+
2525
static std::vector<dynamic_reconfigure::StrParameter> &getVectorForType(dynamic_reconfigure::Config &set, const std::string& /*val*/)
2626
{
2727
return set.strs;
2828
}
29-
29+
3030
static std::vector<dynamic_reconfigure::DoubleParameter> &getVectorForType(dynamic_reconfigure::Config &set, const double /*val*/)
3131
{
3232
return set.doubles;
3333
}
34-
34+
3535
static const std::vector<dynamic_reconfigure::BoolParameter> &getVectorForType(const dynamic_reconfigure::Config &set, const bool /*val*/)
3636
{
3737
return set.bools;
3838
}
39-
39+
4040
static const std::vector<dynamic_reconfigure::IntParameter> &getVectorForType(const dynamic_reconfigure::Config &set, const int /*val*/)
4141
{
4242
return set.ints;
4343
}
44-
44+
4545
static const std::vector<dynamic_reconfigure::StrParameter> &getVectorForType(const dynamic_reconfigure::Config &set, const std::string& /*val*/)
4646
{
4747
return set.strs;
4848
}
49-
49+
5050
static const std::vector<dynamic_reconfigure::DoubleParameter> &getVectorForType(const dynamic_reconfigure::Config &set, const double /*val*/)
5151
{
5252
return set.doubles;
5353
}
54-
54+
5555
static dynamic_reconfigure::BoolParameter makeKeyValuePair(const std::string &name, const bool val)
5656
{
5757
dynamic_reconfigure::BoolParameter param;
@@ -109,7 +109,7 @@ class ConfigTools
109109
}
110110

111111
template<class T>
112-
static void appendGroup(dynamic_reconfigure::Config &set, const std::string &name, int id, int parent, const T &val)
112+
static void appendGroup(dynamic_reconfigure::Config &set, const std::string &name, int id, int parent, const T &val)
113113
{
114114
dynamic_reconfigure::GroupState msg;
115115
msg.name = name;

include/dynamic_reconfigure/server.h

+8-8
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,7 @@
3737
3838
Author: Blaise Gassend
3939
40-
Handles synchronizing node state with the configuration server, and
40+
Handles synchronizing node state with the configuration server, and
4141
handling of services to get and set configuration.
4242
4343
*/
@@ -60,7 +60,7 @@ namespace dynamic_reconfigure
6060
/**
6161
* Keeps track of the reconfigure callback function.
6262
*/
63-
template <class ConfigType>
63+
template <class ConfigType>
6464
class Server
6565
{
6666
public:
@@ -81,7 +81,7 @@ class Server
8181
}
8282

8383
typedef boost::function<void(ConfigType &, uint32_t level)> CallbackType;
84-
84+
8585
void setCallback(const CallbackType &callback)
8686
{
8787
boost::recursive_mutex::scoped_lock lock(mutex_);
@@ -181,10 +181,10 @@ class Server
181181
boost::recursive_mutex::scoped_lock lock(mutex_);
182182
set_service_ = node_handle_.advertiseService("set_parameters",
183183
&Server<ConfigType>::setConfigCallback, this);
184-
184+
185185
descr_pub_ = node_handle_.advertise<dynamic_reconfigure::ConfigDescription>("parameter_descriptions", 1, true);
186186
descr_pub_.publish(ConfigType::__getDescriptionMessage__());
187-
187+
188188
update_pub_ = node_handle_.advertise<dynamic_reconfigure::Config>("parameter_updates", 1, true);
189189
ConfigType init_config = ConfigType::__getDefault__();
190190
init_config.__fromServer__(node_handle_);
@@ -210,7 +210,7 @@ class Server
210210
ROS_DEBUG("setCallback did not call callback because it was zero."); /// @todo kill this line.
211211
}
212212

213-
bool setConfigCallback(dynamic_reconfigure::Reconfigure::Request &req,
213+
bool setConfigCallback(dynamic_reconfigure::Reconfigure::Request &req,
214214
dynamic_reconfigure::Reconfigure::Response &rsp)
215215
{
216216
boost::recursive_mutex::scoped_lock lock(mutex_);
@@ -219,14 +219,14 @@ class Server
219219
new_config.__fromMessage__(req.config);
220220
new_config.__clamp__();
221221
uint32_t level = config_.__level__(new_config);
222-
222+
223223
callCallback(new_config, level);
224224

225225
updateConfigInternal(new_config);
226226
new_config.__toMessage__(rsp.config);
227227
return true;
228228
}
229-
229+
230230
void updateConfigInternal(const ConfigType &config)
231231
{
232232
boost::recursive_mutex::scoped_lock lock(mutex_);

scripts/dynparam

+9-9
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,7 @@
3737
NAME='dynparam'
3838
import roslib; roslib.load_manifest('dynamic_reconfigure')
3939
import rospy
40-
import optparse
40+
import optparse
4141
import sys
4242
import yaml
4343
import dynamic_reconfigure.client
@@ -50,7 +50,7 @@ def do_list():
5050

5151
def do_set_from_parameters():
5252
usage = """Usage: %prog set_from_parameters [options] node
53-
53+
5454
Example command line:
5555
dynparam set_from_parameters wge100_camera _camera_url:=foo
5656
@@ -77,7 +77,7 @@ Example launch file:
7777
except KeyError:
7878
print >> sys.stderr, 'error updating parameters: no parameters found on parameter server'
7979
return
80-
80+
8181
set_params(node, params, timeout=options.timeout)
8282

8383
def do_set():
@@ -126,7 +126,7 @@ Examples:
126126

127127
def do_get():
128128
usage = "Usage: %prog get [options] node"
129-
129+
130130
parser = optparse.OptionParser(usage=usage, prog=NAME)
131131
add_timeout_option(parser)
132132
options, args = parser.parse_args(myargv[2:])
@@ -143,7 +143,7 @@ def do_get():
143143

144144
def do_load():
145145
usage = "Usage: %prog load [options] node file"
146-
146+
147147
parser = optparse.OptionParser(usage=usage, prog=NAME)
148148
add_timeout_option(parser)
149149
options, args = parser.parse_args(myargv[2:])
@@ -168,7 +168,7 @@ def do_load():
168168

169169
def do_dump():
170170
usage = "Usage: %prog dump [options] node file"
171-
171+
172172
parser = optparse.OptionParser(usage=usage, prog=NAME)
173173
add_timeout_option(parser)
174174
options, args = parser.parse_args(myargv[2:])
@@ -179,7 +179,7 @@ def do_dump():
179179
elif len(args) > 2:
180180
parser.error("too many arguments")
181181
node, path = args[0], args[1]
182-
182+
183183
connect()
184184
params = get_params(node, timeout=options.timeout)
185185
if params is not None:
@@ -204,7 +204,7 @@ def set_params(node, params, timeout=None):
204204
print 'error updating parameters: ' + str(e)
205205

206206
def add_timeout_option(parser):
207-
parser.add_option('-t', '--timeout', action='store', type='float', default=None, help='timeout in secs')
207+
parser.add_option('-t', '--timeout', action='store', type='float', default=None, help='timeout in secs')
208208

209209
def print_usage():
210210
print """dynparam is a command-line tool for getting, setting, and
@@ -230,7 +230,7 @@ if __name__ == '__main__':
230230
if len(myargv) == 1:
231231
print_usage()
232232
else:
233-
cmd = myargv[1]
233+
cmd = myargv[1]
234234
try:
235235
if cmd == 'list': do_list()
236236
elif cmd == 'set_from_parameters': do_set_from_parameters()

src/dynamic_reconfigure/__init__.py

+2-2
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,7 @@
3131
# POSSIBILITY OF SUCH DAMAGE.
3232

3333
"""
34-
Python client API for dynamic_reconfigure (L{Client}) as well as
34+
Python client API for dynamic_reconfigure (L{Client}) as well as
3535
example server implementation (L{Server}).
3636
"""
3737

@@ -56,7 +56,7 @@ class DynamicReconfigureCallbackException(DynamicReconfigureException):
5656

5757
def find_reconfigure_services():
5858
import rosservice
59-
return sorted([s[:-len('/set_parameters')] for s in rosservice.get_service_list() if s.endswith('/set_parameters')])
59+
return sorted([s[:-len('/set_parameters')] for s in rosservice.get_service_list() if s.endswith('/set_parameters')])
6060

6161
def get_parameter_names(descr):
6262
return descr.defaults.keys()

src/dynamic_reconfigure/client.py

+13-13
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,7 @@
3131
# POSSIBILITY OF SUCH DAMAGE.
3232

3333
"""
34-
Python client API for dynamic_reconfigure (L{DynamicReconfigureClient}) as well as
34+
Python client API for dynamic_reconfigure (L{DynamicReconfigureClient}) as well as
3535
example server implementation (L{DynamicReconfigureServer}).
3636
"""
3737

@@ -42,7 +42,7 @@
4242
except:
4343
pass
4444
import rospy
45-
import rosservice
45+
import rosservice
4646
import sys
4747
import threading
4848
import time
@@ -63,7 +63,7 @@ class Client(object):
6363
def __init__(self, name, timeout=None, config_callback=None, description_callback=None):
6464
"""
6565
Connect to dynamic_reconfigure server and return a client object
66-
66+
6767
@param name: name of the server to connect to (usually the node name)
6868
@type name: str
6969
@param timeout: time to wait before giving up
@@ -75,15 +75,15 @@ def __init__(self, name, timeout=None, config_callback=None, description_callbac
7575
self.config = None
7676
self.param_description = None
7777
self.group_description = None
78-
78+
7979
self._param_types = None
8080

8181
self._cv = threading.Condition()
8282

8383
self._config_callback = config_callback
8484
self._description_callback = description_callback
8585

86-
self._set_service = self._get_service_proxy('set_parameters', timeout)
86+
self._set_service = self._get_service_proxy('set_parameters', timeout)
8787
self._descriptions_sub = self._get_subscriber('parameter_descriptions', ConfigDescrMsg, self._descriptions_msg)
8888
self._updates_sub = self._get_subscriber('parameter_updates', ConfigMsg, self._updates_msg)
8989

@@ -100,7 +100,7 @@ def get_configuration(self, timeout=None):
100100
if timeout is None or timeout == 0.0:
101101
if self.get_configuration(timeout=1.0) is None:
102102
print >> sys.stderr, 'Waiting for configuration...'
103-
103+
104104
with self._cv:
105105
while self.config is None:
106106
if rospy.is_shutdown():
@@ -123,7 +123,7 @@ def get_parameter_descriptions(self, timeout=None):
123123
"""
124124
UNSTABLE. Return a description of the parameters for the server.
125125
Do not use this method as the type that is returned may change.
126-
126+
127127
@param timeout: time to wait before giving up
128128
@type timeout: float
129129
"""
@@ -184,7 +184,7 @@ def update_configuration(self, changes):
184184
dest_type = self._param_types.get(name)
185185
if dest_type is None:
186186
raise DynamicReconfigureParameterException('don\'t know parameter: %s' % name)
187-
187+
188188
try:
189189
found = False
190190
descr = [x for x in self.param_description if x['name'].lower() == name.lower()][0]
@@ -237,7 +237,7 @@ def update_groups(self, changes):
237237
@param changes: dictionary of key value pairs for the parameters that are changing
238238
@type changes: {str: value}
239239
"""
240-
240+
241241
descr = self.get_group_descriptions()
242242

243243
groups = []
@@ -248,7 +248,7 @@ def update_state(group, description):
248248
else:
249249
update_state(group, g)
250250
return description
251-
251+
252252
for change in changes:
253253
descr = update_state(change, descr)
254254

@@ -279,7 +279,7 @@ def set_config_callback(self, value):
279279

280280
config_callback = property(get_config_callback, set_config_callback)
281281

282-
## description_callback
282+
## description_callback
283283

284284
def get_description_callback(self):
285285
"""
@@ -315,14 +315,14 @@ def _get_service_proxy(self, suffix, timeout):
315315

316316
def _get_subscriber(self, suffix, type, callback):
317317
topic_name = rospy.resolve_name(self.name + '/' + suffix)
318-
318+
319319
return rospy.Subscriber(topic_name, type, callback=callback)
320320

321321
def _updates_msg(self, msg):
322322
if self.group_description is None:
323323
self.get_group_descriptions()
324324
self.config = decode_config(msg, self.group_description)
325-
325+
326326
with self._cv:
327327
self._cv.notifyAll()
328328
if self._config_callback is not None:

0 commit comments

Comments
 (0)