21 #include <dynamic_reconfigure/server.h>
22 #include <cob_omni_drive_controller/SteerCtrlConfig.h>
37 return setup(root_nh, controller_nh);
56 boost::recursive_mutex::scoped_try_lock lock(
mutex);
63 boost::recursive_mutex::scoped_lock lock(
mutex);
70 SteerCtrlConfig config;
71 copy(config, params.front().pos_ctrl);
77 SteerCtrlConfig config;
78 copy(config, params[i].pos_ctrl);
79 dr->setConfigDefault(config);
80 dr->updateConfig(config);
88 params.
dDamp = config.damp;
89 params.
dVirtM = config.virt_mass;
95 config.damp = params.
dDamp;
96 config.virt_mass = params.
dVirtM;
102 ROS_INFO(
"configure all steers: s: %lf, d: %lf, m: %lf, v: %lf, a: %lf", config.spring, config.damp, config.virt_mass, config.d_phi_max, config.dd_phi_max);
112 void setForOne(
size_t i, SteerCtrlConfig &config, uint32_t ) {
113 ROS_INFO(
"configure steer %d: s: %lf, d: %lf, m: %lf, v: %lf, a: %lf", (
int)i, config.spring, config.damp, config.virt_mass, config.d_phi_max, config.dd_phi_max);