@@ -160,9 +160,12 @@ controller_interface::return_type DiffDriveController::update_and_write_commands
160160 const double left_wheel_radius = params_.left_wheel_radius_multiplier * params_.wheel_radius ;
161161 const double right_wheel_radius = params_.right_wheel_radius_multiplier * params_.wheel_radius ;
162162
163+ // Update odometry
164+ bool odometry_updated = false ;
163165 if (params_.open_loop )
164166 {
165- odometry_.updateOpenLoop (linear_command, angular_command, time);
167+ odometry_updated =
168+ odometry_.try_update_open_loop (linear_command, angular_command, period.seconds ());
166169 }
167170 else
168171 {
@@ -200,62 +203,65 @@ controller_interface::return_type DiffDriveController::update_and_write_commands
200203
201204 if (params_.position_feedback )
202205 {
203- odometry_.update (left_feedback_mean, right_feedback_mean, time);
206+ odometry_updated =
207+ odometry_.update_from_pos (left_feedback_mean, right_feedback_mean, period.seconds ());
204208 }
205209 else
206210 {
207- odometry_.updateFromVelocity (
208- left_feedback_mean * left_wheel_radius * period.seconds (),
209- right_feedback_mean * right_wheel_radius * period.seconds (), time);
211+ odometry_updated =
212+ odometry_.update_from_vel (left_feedback_mean, right_feedback_mean, period.seconds ());
210213 }
211214 }
212215
213- tf2::Quaternion orientation;
214- orientation.setRPY (0.0 , 0.0 , odometry_.getHeading ());
215-
216- bool should_publish = false ;
217- try
216+ if (odometry_updated)
218217 {
219- if (previous_publish_timestamp_ + publish_period_ < time)
218+ tf2::Quaternion orientation;
219+ orientation.setRPY (0.0 , 0.0 , odometry_.getHeading ());
220+
221+ bool should_publish = false ;
222+ try
220223 {
221- previous_publish_timestamp_ += publish_period_;
222- should_publish = true ;
224+ if (previous_publish_timestamp_ + publish_period_ <= time)
225+ {
226+ previous_publish_timestamp_ += publish_period_;
227+ should_publish = true ;
228+ }
223229 }
224- }
225- catch (const std::runtime_error &)
226- {
227- // Handle exceptions when the time source changes and initialize publish timestamp
228- previous_publish_timestamp_ = time;
229- should_publish = true ;
230- }
231-
232- if (should_publish)
233- {
234- if (realtime_odometry_publisher_)
230+ catch (const std::runtime_error &)
235231 {
236- odometry_message_.header .stamp = time;
237- odometry_message_.pose .pose .position .x = odometry_.getX ();
238- odometry_message_.pose .pose .position .y = odometry_.getY ();
239- odometry_message_.pose .pose .orientation .x = orientation.x ();
240- odometry_message_.pose .pose .orientation .y = orientation.y ();
241- odometry_message_.pose .pose .orientation .z = orientation.z ();
242- odometry_message_.pose .pose .orientation .w = orientation.w ();
243- odometry_message_.twist .twist .linear .x = odometry_.getLinear ();
244- odometry_message_.twist .twist .angular .z = odometry_.getAngular ();
245- realtime_odometry_publisher_->try_publish (odometry_message_);
232+ // Handle exceptions when the time source changes and initialize publish timestamp
233+ previous_publish_timestamp_ = time;
234+ should_publish = true ;
246235 }
247236
248- if (params_. enable_odom_tf && realtime_odometry_transform_publisher_ )
237+ if (should_publish )
249238 {
250- auto & transform = odometry_transform_message_.transforms .front ();
251- transform.header .stamp = time;
252- transform.transform .translation .x = odometry_.getX ();
253- transform.transform .translation .y = odometry_.getY ();
254- transform.transform .rotation .x = orientation.x ();
255- transform.transform .rotation .y = orientation.y ();
256- transform.transform .rotation .z = orientation.z ();
257- transform.transform .rotation .w = orientation.w ();
258- realtime_odometry_transform_publisher_->try_publish (odometry_transform_message_);
239+ if (realtime_odometry_publisher_)
240+ {
241+ odometry_message_.header .stamp = time;
242+ odometry_message_.pose .pose .position .x = odometry_.getX ();
243+ odometry_message_.pose .pose .position .y = odometry_.getY ();
244+ odometry_message_.pose .pose .orientation .x = orientation.x ();
245+ odometry_message_.pose .pose .orientation .y = orientation.y ();
246+ odometry_message_.pose .pose .orientation .z = orientation.z ();
247+ odometry_message_.pose .pose .orientation .w = orientation.w ();
248+ odometry_message_.twist .twist .linear .x = odometry_.getLinear ();
249+ odometry_message_.twist .twist .angular .z = odometry_.getAngular ();
250+ realtime_odometry_publisher_->try_publish (odometry_message_);
251+ }
252+
253+ if (params_.enable_odom_tf && realtime_odometry_transform_publisher_)
254+ {
255+ auto & transform = odometry_transform_message_.transforms .front ();
256+ transform.header .stamp = time;
257+ transform.transform .translation .x = odometry_.getX ();
258+ transform.transform .translation .y = odometry_.getY ();
259+ transform.transform .rotation .x = orientation.x ();
260+ transform.transform .rotation .y = orientation.y ();
261+ transform.transform .rotation .z = orientation.z ();
262+ transform.transform .rotation .w = orientation.w ();
263+ realtime_odometry_transform_publisher_->try_publish (odometry_transform_message_);
264+ }
259265 }
260266 }
261267
0 commit comments