Skip to content

Commit 5256a14

Browse files
committed
Add documentation for variables and functions
Includes minor stylistic changes. Signed-off-by: Maganty Rushyendra <[email protected]>
1 parent d0005d7 commit 5256a14

File tree

2 files changed

+31
-26
lines changed

2 files changed

+31
-26
lines changed

src/systems/odometry_publisher/OdometryPublisher.cc

+18-17
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,7 @@ using namespace systems;
4141

4242
class ignition::gazebo::systems::OdometryPublisherPrivate
4343
{
44-
/// \brief Update odometry and publish an odometry message.
44+
/// \brief Calculates odometry and publishes an odometry message.
4545
/// \param[in] _info System update information.
4646
/// \param[in] _ecm The EntityComponentManager of the given simulation
4747
/// instance.
@@ -54,8 +54,10 @@ class ignition::gazebo::systems::OdometryPublisherPrivate
5454
/// \brief Model interface
5555
public: Model model{kNullEntity};
5656

57+
/// \brief Name of the world-fixed coordinate frame for the odometry message.
5758
public: std::string odomFrame;
5859

60+
/// \brief Name of the coordinate frame rigidly attached to the mobile robot base.
5961
public: std::string robotBaseFrame;
6062

6163
/// \brief Update period calculated from <odom__publish_frequency>.
@@ -73,8 +75,10 @@ class ignition::gazebo::systems::OdometryPublisherPrivate
7375
/// \brief Rolling mean accumulators for the angular velocity
7476
public: math::RollingMean angularMean;
7577

78+
/// \brief Initialized flag.
7679
public: bool initialized{false};
7780

81+
/// \brief Current pose of the model in the odom frame.
7882
public: math::Pose3d lastUpdatePose{0, 0, 0, 0, 0, 0};
7983

8084
/// \brief Current timestamp.
@@ -111,7 +115,7 @@ void OdometryPublisher::Configure(const Entity &_entity,
111115
this->dataPtr->odomFrame = "odom";
112116
if (!_sdf->HasElement("odom_frame"))
113117
{
114-
ignwarn << "PlanarMovePlugin missing <odom_frame>, "
118+
ignwarn << "OdometryPublisher system plugin missing <odom_frame>, "
115119
<< "defaults to \"" << this->dataPtr->odomFrame << "\"" << std::endl;
116120
}
117121
else
@@ -122,7 +126,7 @@ void OdometryPublisher::Configure(const Entity &_entity,
122126
this->dataPtr->robotBaseFrame = "base_footprint";
123127
if (!_sdf->HasElement("robot_base_frame"))
124128
{
125-
ignwarn << "PlanarMovePlugin missing <robot_base_frame>, "
129+
ignwarn << "OdometryPublisher system plugin missing <robot_base_frame>, "
126130
<< "defaults to \"" << this->dataPtr->robotBaseFrame << "\"" << std::endl;
127131
}
128132
else
@@ -133,14 +137,14 @@ void OdometryPublisher::Configure(const Entity &_entity,
133137
double odomFreq = _sdf->Get<double>("odom_publish_frequency", 50).first;
134138
if (odomFreq > 0)
135139
{
136-
std::chrono::duration<double> odomPer{1 / odomFreq};
140+
std::chrono::duration<double> period{1 / odomFreq};
137141
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);
139143
}
140144

141145
// Setup odometry
142146
std::string odomTopic{"/model/" + this->dataPtr->model.Name(_ecm) +
143-
"/odometryFoo"};
147+
"/odometry"};
144148
if (_sdf->HasElement("odom_topic"))
145149
odomTopic = _sdf->Get<std::string>("odom_topic");
146150
this->dataPtr->odomPub = this->dataPtr->node.Advertise<msgs::Odometry>(
@@ -188,32 +192,31 @@ void OdometryPublisherPrivate::UpdateOdometry(const ignition::gazebo::UpdateInfo
188192
const ignition::gazebo::EntityComponentManager &_ecm)
189193
{
190194
IGN_PROFILE("DiffDrive::UpdateOdometry");
191-
// Initialize, if not already initialized.
195+
// Record start time.
192196
if (!this->initialized)
193197
{
194198
this->lastUpdateTime = std::chrono::steady_clock::time_point(_info.simTime);
195199
this->initialized = true;
196-
return; //to check why
200+
return;
197201
}
198202

199203
// Construct the odometry message and publish it.
200204
msgs::Odometry msg;
201205

202-
// Compute x, y and heading using velocity
203206
const std::chrono::duration<double> dt =
204207
std::chrono::steady_clock::time_point(_info.simTime) - lastUpdateTime;
205208
// We cannot estimate the speed if the time interval is zero (or near
206209
// zero).
207210
if (math::equal(0.0, dt.count()))
208211
return;
209212

210-
// World to odom transformation
213+
// Get and set robotBaseFrame to odom transformation.
211214
const math::Pose3d pose = worldPose(this->model.Entity(), _ecm);
212215
msg.mutable_pose()->mutable_position()->set_x(pose.Pos().X());
213216
msg.mutable_pose()->mutable_position()->set_y(pose.Pos().Y());
214217
msgs::Set(msg.mutable_pose()->mutable_orientation(), pose.Rot());
215218

216-
// Get linear and angular displacements from last updated pose
219+
// Get linear and angular displacements from last updated pose.
217220
double linearDisplacementX = pose.Pos().X() - this->lastUpdatePose.Pos().X();
218221
double linearDisplacementY = pose.Pos().Y() - this->lastUpdatePose.Pos().Y();
219222

@@ -223,8 +226,7 @@ void OdometryPublisherPrivate::UpdateOdometry(const ignition::gazebo::UpdateInfo
223226
while (currentYaw > lastYaw + M_PI) currentYaw -= 2 * M_PI;
224227
const float angularDiff = currentYaw - lastYaw;
225228

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.
228230
double linearVelocityX = (cosf(currentYaw) * linearDisplacementX
229231
+ sinf(currentYaw) * linearDisplacementX) / dt.count();
230232
double linearVelocityY = (cosf(currentYaw) * linearDisplacementY
@@ -236,30 +238,29 @@ void OdometryPublisherPrivate::UpdateOdometry(const ignition::gazebo::UpdateInfo
236238
msg.mutable_twist()->mutable_linear()->set_y(this->linearMean.second.Mean());
237239
msg.mutable_twist()->mutable_angular()->set_z(this->angularMean.Mean());
238240

239-
// Set the time stamp in the header
241+
// Set the time stamp in the header.
240242
msg.mutable_header()->mutable_stamp()->CopyFrom(
241243
convert<msgs::Time>(_info.simTime));
242244

243245
// Set the frame ids.
244246
auto frame = msg.mutable_header()->add_data();
245247
frame->set_key("frame_id");
246-
frame->add_value(this->model.Name(_ecm) + "/" +odomFrame);
248+
frame->add_value(this->model.Name(_ecm) + "/" + odomFrame);
247249
auto childFrame = msg.mutable_header()->add_data();
248250
childFrame->set_key("child_frame_id");
249251
childFrame->add_value(this->model.Name(_ecm) + "/" + robotBaseFrame);
250252

251253
this->lastUpdatePose = pose;
252254
this->lastUpdateTime = std::chrono::steady_clock::time_point(_info.simTime);
253255

254-
// Throttle publishing
256+
// Throttle publishing.
255257
auto diff = _info.simTime - this->lastOdomPubTime;
256258
if (diff > std::chrono::steady_clock::duration::zero() &&
257259
diff < this->odomPubPeriod)
258260
{
259261
return;
260262
}
261263
this->lastOdomPubTime = _info.simTime;
262-
// Publish the message
263264
this->odomPub.Publish(msg);
264265
}
265266

src/systems/odometry_publisher/OdometryPublisher.hh

+13-9
Original file line numberDiff line numberDiff line change
@@ -17,8 +17,6 @@
1717
#ifndef IGNITION_GAZEBO_SYSTEMS_ODOMETRYPUBLISHER_HH_
1818
#define IGNITION_GAZEBO_SYSTEMS_ODOMETRYPUBLISHER_HH_
1919

20-
#include <memory>
21-
2220
#include <ignition/gazebo/System.hh>
2321

2422
namespace ignition
@@ -32,20 +30,26 @@ namespace systems
3230
// Forward declaration
3331
class OdometryPublisherPrivate;
3432

35-
/// \brief Odometry Publisher
33+
/// \brief Odometry Publisher which can be attached to any entity in
34+
/// order to periodically publish its odometry in the form of
35+
/// ignition::msgs::Odometry messages.
3636
///
3737
/// # System Parameters
38-
/// `<odom_topic>`: Custom topic on which this system will publish odometry
39-
/// messages. This element if optional, and the default value is
40-
/// `/model/{name_of_model}/odometry`.
4138
///
42-
/// `<odom_frame>`:
39+
/// `<odom_frame>`: Name of the world-fixed coordinate frame for the
40+
// odometry message. This element is optional, and the default value
41+
/// is `odom`.
42+
///
43+
/// `<robot_base_frame>`: Name of the coordinate frame rigidly attached
44+
/// to the mobile robot base. This element is optional, and the default
45+
/// value is `robot_base_frame`.
4346
///
4447
/// `<odom_publish_frequency>`: Odometry publication frequency. This
4548
/// element is optional, and the default value is 50Hz.
4649
///
47-
/// `<robot_base_frame>`:
48-
///
50+
/// `<odom_topic>`: Custom topic on which this system will publish odometry
51+
/// messages. This element is optional, and the default value is
52+
/// `/model/{name_of_model}/odometry`.
4953
class IGNITION_GAZEBO_VISIBLE OdometryPublisher
5054
: public System,
5155
public ISystemConfigure,

0 commit comments

Comments
 (0)