Skip to content

Commit 8595a5d

Browse files
author
Enrique Fernandez
committed
Make dynamic reconfigure params RT-safe
1 parent 055f305 commit 8595a5d

File tree

2 files changed

+77
-25
lines changed

2 files changed

+77
-25
lines changed

diff_drive_controller/include/diff_drive_controller/diff_drive_controller.h

+21-1
Original file line numberDiff line numberDiff line change
@@ -139,10 +139,30 @@ namespace diff_drive_controller
139139
Odometry odometry_;
140140
geometry_msgs::TransformStamped odom_frame_;
141141

142-
/// Dynamic reconfigure server:
142+
/// Dynamic reconfigure server related:
143143
typedef dynamic_reconfigure::Server<DiffDriveControllerConfig> ReconfigureServer;
144144
boost::shared_ptr<ReconfigureServer> cfg_server_;
145145

146+
struct DynamicParams
147+
{
148+
double wheel_separation_multiplier;
149+
double left_wheel_radius_multiplier;
150+
double right_wheel_radius_multiplier;
151+
152+
double k_l;
153+
double k_r;
154+
155+
DynamicParams()
156+
: wheel_separation_multiplier(1.0)
157+
, left_wheel_radius_multiplier(1.0)
158+
, right_wheel_radius_multiplier(1.0)
159+
, k_l(1.0)
160+
, k_r(1.0)
161+
{}
162+
};
163+
realtime_tools::RealtimeBuffer<DynamicParams> dynamic_params_;
164+
DynamicParams dynamic_params_struct_;
165+
146166
/// Wheel separation, wrt the midpoint of the wheel width:
147167
double wheel_separation_;
148168

diff_drive_controller/src/diff_drive_controller.cpp

+56-24
Original file line numberDiff line numberDiff line change
@@ -134,6 +134,7 @@ namespace diff_drive_controller
134134
DiffDriveController::DiffDriveController()
135135
: open_loop_(false)
136136
, command_struct_()
137+
, dynamic_params_struct_()
137138
, wheel_separation_(0.0)
138139
, wheel_radius_(0.0)
139140
, wheel_separation_multiplier_(1.0)
@@ -279,6 +280,16 @@ namespace diff_drive_controller
279280
"Measurement Covariance Model params : k_l " << k_l_
280281
<< ", k_r " << k_r_);
281282

283+
dynamic_params_struct_.wheel_separation_multiplier = wheel_separation_multiplier_;
284+
285+
dynamic_params_struct_.left_wheel_radius_multiplier = left_wheel_radius_multiplier_;
286+
dynamic_params_struct_.right_wheel_radius_multiplier = right_wheel_radius_multiplier_;
287+
288+
dynamic_params_struct_.k_l = k_l_;
289+
dynamic_params_struct_.k_r = k_r_;
290+
291+
dynamic_params_.writeFromNonRT(dynamic_params_struct_);
292+
282293
setOdomPubFields(root_nh, controller_nh);
283294

284295
// Set dynamic reconfigure server callback:
@@ -303,6 +314,35 @@ namespace diff_drive_controller
303314

304315
void DiffDriveController::update(const ros::Time& time, const ros::Duration& period)
305316
{
317+
// UPDATE DYNAMIC PARAMS
318+
// Retreive dynamic params:
319+
DynamicParams dynamic_params = *(dynamic_params_.readFromRT());
320+
321+
// Update dynamic params:
322+
// NOTE we cannot do the following because there's no writFromRT!
323+
// if (dynamic_params.changed)
324+
// {
325+
// dynamic_params.changed = false;
326+
// dynamic_params_.writeFromRT(dynamic_params);
327+
//
328+
// ...
329+
// }
330+
wheel_separation_multiplier_ = dynamic_params.wheel_separation_multiplier;
331+
left_wheel_radius_multiplier_ = dynamic_params.left_wheel_radius_multiplier;
332+
right_wheel_radius_multiplier_ = dynamic_params.right_wheel_radius_multiplier;
333+
334+
k_l_ = dynamic_params.k_l;
335+
k_r_ = dynamic_params.k_r;
336+
337+
// Apply multipliers:
338+
const double ws = wheel_separation_multiplier_ * wheel_separation_;
339+
const double wrl = left_wheel_radius_multiplier_ * wheel_radius_;
340+
const double wrr = right_wheel_radius_multiplier_ * wheel_radius_;
341+
342+
// Set the odometry parameters:
343+
odometry_.setWheelParams(ws, wrl, wrr);
344+
odometry_.setMeasCovarianceParams(k_l_, k_r_);
345+
306346
// COMPUTE AND PUBLISH ODOMETRY
307347
if (open_loop_)
308348
{
@@ -385,11 +425,6 @@ namespace diff_drive_controller
385425
limiter_ang_.limit(curr_cmd.ang, last_cmd_.ang, cmd_dt);
386426
last_cmd_ = curr_cmd;
387427

388-
// Apply multipliers:
389-
const double ws = wheel_separation_multiplier_ * wheel_separation_;
390-
const double wrl = left_wheel_radius_multiplier_ * wheel_radius_;
391-
const double wrr = right_wheel_radius_multiplier_ * wheel_radius_;
392-
393428
// Compute wheels velocities:
394429
const double vel_left = (curr_cmd.lin - curr_cmd.ang * ws / 2.0)/wrl;
395430
const double vel_right = (curr_cmd.lin + curr_cmd.ang * ws / 2.0)/wrr;
@@ -450,29 +485,26 @@ namespace diff_drive_controller
450485
void DiffDriveController::reconfigureCallback(
451486
DiffDriveControllerConfig& config, uint32_t level)
452487
{
453-
// @todo make this real-time safe!!!
454-
wheel_separation_multiplier_ = config.wheel_separation_multiplier;
488+
dynamic_params_struct_.wheel_separation_multiplier = config.wheel_separation_multiplier;
455489

456-
left_wheel_radius_multiplier_ = config.left_wheel_radius_multiplier;
457-
right_wheel_radius_multiplier_ = config.right_wheel_radius_multiplier;
490+
dynamic_params_struct_.left_wheel_radius_multiplier = config.left_wheel_radius_multiplier;
491+
dynamic_params_struct_.right_wheel_radius_multiplier = config.right_wheel_radius_multiplier;
458492

459-
k_l_ = config.k_l;
460-
k_r_ = config.k_r;
493+
dynamic_params_struct_.k_l = config.k_l;
494+
dynamic_params_struct_.k_r = config.k_r;
461495

462-
// Set the odometry parameters
463-
const double ws = wheel_separation_multiplier_ * wheel_separation_;
464-
const double wrl = left_wheel_radius_multiplier_ * wheel_radius_;
465-
const double wrr = right_wheel_radius_multiplier_ * wheel_radius_;
466-
odometry_.setWheelParams(ws, wrl, wrr);
467-
ROS_INFO_STREAM_NAMED(name_,
468-
"Odometry params : wheel separation " << ws
469-
<< ", left wheel radius " << wrl
470-
<< ", right wheel radius " << wrr);
496+
dynamic_params_.writeFromNonRT(dynamic_params_struct_);
471497

472-
odometry_.setMeasCovarianceParams(k_l_, k_r_);
473-
ROS_INFO_STREAM_NAMED(name_,
474-
"Measurement Covariance Model params : k_l " << k_l_
475-
<< ", k_r " << k_r_);
498+
ROS_DEBUG_STREAM_NAMED(name_,
499+
"Reconfigured Odometry params. "
500+
<< "wheel separation: " << dynamic_params_struct_.wheel_separation_multiplier << ", "
501+
<< "left wheel radius: " << dynamic_params_struct_.left_wheel_radius_multiplier << ", "
502+
<< "right wheel radius: " << dynamic_params_struct_.left_wheel_radius_multiplier);
503+
504+
ROS_DEBUG_STREAM_NAMED(name_,
505+
"Reconfigured Measurement Covariance Model params. "
506+
<< "k_l: " << dynamic_params_struct_.k_l << ", "
507+
<< "k_r: " << dynamic_params_struct_.k_r);
476508
}
477509

478510
bool DiffDriveController::getWheelNames(ros::NodeHandle& controller_nh,

0 commit comments

Comments
 (0)