@@ -41,7 +41,7 @@ using namespace systems;
41
41
42
42
class ignition ::gazebo::systems::OdometryPublisherPrivate
43
43
{
44
- // / \brief Update odometry and publish an odometry message.
44
+ // / \brief Calculates odometry and publishes an odometry message.
45
45
// / \param[in] _info System update information.
46
46
// / \param[in] _ecm The EntityComponentManager of the given simulation
47
47
// / instance.
@@ -54,8 +54,10 @@ class ignition::gazebo::systems::OdometryPublisherPrivate
54
54
// / \brief Model interface
55
55
public: Model model{kNullEntity };
56
56
57
+ // / \brief Name of the world-fixed coordinate frame for the odometry message.
57
58
public: std::string odomFrame;
58
59
60
+ // / \brief Name of the coordinate frame rigidly attached to the mobile robot base.
59
61
public: std::string robotBaseFrame;
60
62
61
63
// / \brief Update period calculated from <odom__publish_frequency>.
@@ -73,8 +75,10 @@ class ignition::gazebo::systems::OdometryPublisherPrivate
73
75
// / \brief Rolling mean accumulators for the angular velocity
74
76
public: math::RollingMean angularMean;
75
77
78
+ // / \brief Initialized flag.
76
79
public: bool initialized{false };
77
80
81
+ // / \brief Current pose of the model in the odom frame.
78
82
public: math::Pose3d lastUpdatePose{0 , 0 , 0 , 0 , 0 , 0 };
79
83
80
84
// / \brief Current timestamp.
@@ -111,7 +115,7 @@ void OdometryPublisher::Configure(const Entity &_entity,
111
115
this ->dataPtr ->odomFrame = " odom" ;
112
116
if (!_sdf->HasElement (" odom_frame" ))
113
117
{
114
- ignwarn << " PlanarMovePlugin missing <odom_frame>, "
118
+ ignwarn << " OdometryPublisher system plugin missing <odom_frame>, "
115
119
<< " defaults to \" " << this ->dataPtr ->odomFrame << " \" " << std::endl;
116
120
}
117
121
else
@@ -122,7 +126,7 @@ void OdometryPublisher::Configure(const Entity &_entity,
122
126
this ->dataPtr ->robotBaseFrame = " base_footprint" ;
123
127
if (!_sdf->HasElement (" robot_base_frame" ))
124
128
{
125
- ignwarn << " PlanarMovePlugin missing <robot_base_frame>, "
129
+ ignwarn << " OdometryPublisher system plugin missing <robot_base_frame>, "
126
130
<< " defaults to \" " << this ->dataPtr ->robotBaseFrame << " \" " << std::endl;
127
131
}
128
132
else
@@ -133,14 +137,14 @@ void OdometryPublisher::Configure(const Entity &_entity,
133
137
double odomFreq = _sdf->Get <double >(" odom_publish_frequency" , 50 ).first ;
134
138
if (odomFreq > 0 )
135
139
{
136
- std::chrono::duration<double > odomPer {1 / odomFreq};
140
+ std::chrono::duration<double > period {1 / odomFreq};
137
141
this ->dataPtr ->odomPubPeriod =
138
- std::chrono::duration_cast<std::chrono::steady_clock::duration>(odomPer );
142
+ std::chrono::duration_cast<std::chrono::steady_clock::duration>(period );
139
143
}
140
144
141
145
// Setup odometry
142
146
std::string odomTopic{" /model/" + this ->dataPtr ->model .Name (_ecm) +
143
- " /odometryFoo " };
147
+ " /odometry " };
144
148
if (_sdf->HasElement (" odom_topic" ))
145
149
odomTopic = _sdf->Get <std::string>(" odom_topic" );
146
150
this ->dataPtr ->odomPub = this ->dataPtr ->node .Advertise <msgs::Odometry>(
@@ -188,32 +192,31 @@ void OdometryPublisherPrivate::UpdateOdometry(const ignition::gazebo::UpdateInfo
188
192
const ignition::gazebo::EntityComponentManager &_ecm)
189
193
{
190
194
IGN_PROFILE (" DiffDrive::UpdateOdometry" );
191
- // Initialize, if not already initialized .
195
+ // Record start time .
192
196
if (!this ->initialized )
193
197
{
194
198
this ->lastUpdateTime = std::chrono::steady_clock::time_point (_info.simTime );
195
199
this ->initialized = true ;
196
- return ; // to check why
200
+ return ;
197
201
}
198
202
199
203
// Construct the odometry message and publish it.
200
204
msgs::Odometry msg;
201
205
202
- // Compute x, y and heading using velocity
203
206
const std::chrono::duration<double > dt =
204
207
std::chrono::steady_clock::time_point (_info.simTime ) - lastUpdateTime;
205
208
// We cannot estimate the speed if the time interval is zero (or near
206
209
// zero).
207
210
if (math::equal (0.0 , dt.count ()))
208
211
return ;
209
212
210
- // World to odom transformation
213
+ // Get and set robotBaseFrame to odom transformation.
211
214
const math::Pose3d pose = worldPose (this ->model .Entity (), _ecm);
212
215
msg.mutable_pose ()->mutable_position ()->set_x (pose.Pos ().X ());
213
216
msg.mutable_pose ()->mutable_position ()->set_y (pose.Pos ().Y ());
214
217
msgs::Set (msg.mutable_pose ()->mutable_orientation (), pose.Rot ());
215
218
216
- // Get linear and angular displacements from last updated pose
219
+ // Get linear and angular displacements from last updated pose.
217
220
double linearDisplacementX = pose.Pos ().X () - this ->lastUpdatePose .Pos ().X ();
218
221
double linearDisplacementY = pose.Pos ().Y () - this ->lastUpdatePose .Pos ().Y ();
219
222
@@ -223,8 +226,7 @@ void OdometryPublisherPrivate::UpdateOdometry(const ignition::gazebo::UpdateInfo
223
226
while (currentYaw > lastYaw + M_PI) currentYaw -= 2 * M_PI;
224
227
const float angularDiff = currentYaw - lastYaw;
225
228
226
- // auto odom_lin_vel_comp = linearVelocity->Data();
227
- // Get velocities in child frame (i.e. base_link frame) and add to message
229
+ // Get velocities in robotBaseFrame and add to message.
228
230
double linearVelocityX = (cosf (currentYaw) * linearDisplacementX
229
231
+ sinf (currentYaw) * linearDisplacementX) / dt.count ();
230
232
double linearVelocityY = (cosf (currentYaw) * linearDisplacementY
@@ -236,30 +238,29 @@ void OdometryPublisherPrivate::UpdateOdometry(const ignition::gazebo::UpdateInfo
236
238
msg.mutable_twist ()->mutable_linear ()->set_y (this ->linearMean .second .Mean ());
237
239
msg.mutable_twist ()->mutable_angular ()->set_z (this ->angularMean .Mean ());
238
240
239
- // Set the time stamp in the header
241
+ // Set the time stamp in the header.
240
242
msg.mutable_header ()->mutable_stamp ()->CopyFrom (
241
243
convert<msgs::Time>(_info.simTime ));
242
244
243
245
// Set the frame ids.
244
246
auto frame = msg.mutable_header ()->add_data ();
245
247
frame->set_key (" frame_id" );
246
- frame->add_value (this ->model .Name (_ecm) + " /" +odomFrame);
248
+ frame->add_value (this ->model .Name (_ecm) + " /" + odomFrame);
247
249
auto childFrame = msg.mutable_header ()->add_data ();
248
250
childFrame->set_key (" child_frame_id" );
249
251
childFrame->add_value (this ->model .Name (_ecm) + " /" + robotBaseFrame);
250
252
251
253
this ->lastUpdatePose = pose;
252
254
this ->lastUpdateTime = std::chrono::steady_clock::time_point (_info.simTime );
253
255
254
- // Throttle publishing
256
+ // Throttle publishing.
255
257
auto diff = _info.simTime - this ->lastOdomPubTime ;
256
258
if (diff > std::chrono::steady_clock::duration::zero () &&
257
259
diff < this ->odomPubPeriod )
258
260
{
259
261
return ;
260
262
}
261
263
this ->lastOdomPubTime = _info.simTime ;
262
- // Publish the message
263
264
this ->odomPub .Publish (msg);
264
265
}
265
266
0 commit comments