Skip to content

Commit 4fde852

Browse files
mabelzhangazeeyiche033ahcorde
authored
Add tutorial for using the Pose component (gazebosim#2219)
Adds a tutorial on how to use the Pose component, using OdometryPublisher system as an example, because that system depends on only 1 component, good as a standalone example. --------- Signed-off-by: Addisu Z. Taddese <addisu@openrobotics.org> Signed-off-by: Mabel Zhang <mabel@openrobotics.org> Signed-off-by: Ian Chen <ichen@openrobotics.org> Signed-off-by: Mabel Zhang <mabel.m.zhang@gmail.com> Co-authored-by: Addisu Z. Taddese <addisu@openrobotics.org> Co-authored-by: Ian Chen <ichen@openrobotics.org> Co-authored-by: Alejandro Hernández Cordero <ahcorde@gmail.com>
1 parent 2297be7 commit 4fde852

File tree

4 files changed

+102
-9
lines changed

4 files changed

+102
-9
lines changed

src/systems/odometry_publisher/OdometryPublisher.cc

Lines changed: 14 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -59,7 +59,9 @@ class gz::sim::systems::OdometryPublisherPrivate
5959
public: transport::Node node;
6060

6161
/// \brief Model interface
62+
//! [modelDeclaration]
6263
public: Model model{kNullEntity};
64+
//! [modelDeclaration]
6365

6466
/// \brief Name of the world-fixed coordinate frame for the odometry message.
6567
public: std::string odomFrame;
@@ -133,12 +135,14 @@ OdometryPublisher::OdometryPublisher()
133135
}
134136

135137
//////////////////////////////////////////////////
138+
//! [Configure]
136139
void OdometryPublisher::Configure(const Entity &_entity,
137140
const std::shared_ptr<const sdf::Element> &_sdf,
138141
EntityComponentManager &_ecm,
139142
EventManager &/*_eventMgr*/)
140143
{
141144
this->dataPtr->model = Model(_entity);
145+
//! [Configure]
142146

143147
if (!this->dataPtr->model.Valid(_ecm))
144148
{
@@ -233,8 +237,10 @@ void OdometryPublisher::Configure(const Entity &_entity,
233237
}
234238
else
235239
{
240+
//! [definePub]
236241
this->dataPtr->odomPub = this->dataPtr->node.Advertise<msgs::Odometry>(
237242
odomTopicValid);
243+
//! [definePub]
238244
gzmsg << "OdometryPublisher publishing odometry on [" << odomTopicValid
239245
<< "]" << std::endl;
240246
}
@@ -300,15 +306,6 @@ void OdometryPublisher::PreUpdate(const gz::sim::UpdateInfo &_info,
300306
<< std::chrono::duration<double>(_info.dt).count()
301307
<< "s]. System may not work properly." << std::endl;
302308
}
303-
304-
// Create the pose component if it does not exist.
305-
auto pos = _ecm.Component<components::Pose>(
306-
this->dataPtr->model.Entity());
307-
if (!pos)
308-
{
309-
_ecm.CreateComponent(this->dataPtr->model.Entity(),
310-
components::Pose());
311-
}
312309
}
313310

314311
//////////////////////////////////////////////////
@@ -347,7 +344,9 @@ void OdometryPublisherPrivate::UpdateOdometry(
347344
}
348345

349346
// Construct the odometry message and publish it.
347+
//! [declarePoseMsg]
350348
msgs::Odometry msg;
349+
//! [declarePoseMsg]
351350

352351
const std::chrono::duration<double> dt =
353352
std::chrono::steady_clock::time_point(_info.simTime) - lastUpdateTime;
@@ -357,7 +356,10 @@ void OdometryPublisherPrivate::UpdateOdometry(
357356
return;
358357

359358
// Get and set robotBaseFrame to odom transformation.
359+
//! [worldPose]
360360
const math::Pose3d rawPose = worldPose(this->model.Entity(), _ecm);
361+
//! [worldPose]
362+
//! [setPoseMsg]
361363
math::Pose3d pose = rawPose * this->offset;
362364
msg.mutable_pose()->mutable_position()->set_x(pose.Pos().X());
363365
msg.mutable_pose()->mutable_position()->set_y(pose.Pos().Y());
@@ -366,6 +368,7 @@ void OdometryPublisherPrivate::UpdateOdometry(
366368
{
367369
msg.mutable_pose()->mutable_position()->set_z(pose.Pos().Z());
368370
}
371+
//! [setPoseMsg]
369372

370373
// Get linear and angular displacements from last updated pose.
371374
double linearDisplacementX = pose.Pos().X() - this->lastUpdatePose.Pos().X();
@@ -476,7 +479,9 @@ void OdometryPublisherPrivate::UpdateOdometry(
476479
this->lastOdomPubTime = _info.simTime;
477480
if (this->odomPub.Valid())
478481
{
482+
//! [publishMsg]
479483
this->odomPub.Publish(msg);
484+
//! [publishMsg]
480485
}
481486

482487
// Generate odometry with covariance message and publish it.

src/systems/odometry_publisher/OdometryPublisher.hh

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -76,6 +76,13 @@ namespace systems
7676
/// - `<gaussian_noise>`: Standard deviation of the Gaussian noise to be added
7777
/// to pose and twist messages. This element is optional, and the default
7878
/// value is 0.
79+
///
80+
/// ## Components
81+
///
82+
/// This system uses the following components:
83+
///
84+
/// - gz::sim::components::Pose: Pose represented by gz::math::Pose3d. Used
85+
/// to calculate the odometry to publish.
7986
class OdometryPublisher
8087
: public System,
8188
public ISystemConfigure,

tutorials/component_pose.md

Lines changed: 80 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,80 @@
1+
\page posecomponent Case Study: Using the Pose Component
2+
3+
We will show how to use the gz::sim::components::Pose component in a system.
4+
5+
An example usage of the component can be found in the
6+
gz::sim::systems::OdometryPublisher system
7+
([source code](https://github.com/gazebosim/gz-sim/tree/gz-sim8/src/systems/odometry_publisher)),
8+
which reads the pose component of a model through the Model entity, uses the
9+
pose for some calculations, and then publishes the result as a message.
10+
11+
More usage can be found in the
12+
[integration test](https://github.com/gazebosim/gz-sim/blob/gz-sim8/test/integration/odometry_publisher.cc)
13+
for the system, with test worlds `odometry*.sdf`
14+
[here](https://github.com/gazebosim/gz-sim/tree/main/test/worlds).
15+
16+
### Objects of interest
17+
18+
- gz::sim::components::Pose: A component containing pose information
19+
- gz::math::Pose3d: The actual data underlying a pose component
20+
- gz::sim::systems::OdometryPublisher: A system that reads the pose component
21+
of a model
22+
- gz::sim::Model: The type underlying a model entity (gz::sim::Entity)
23+
24+
### Find the model entity
25+
26+
First, we will need access to an entity, the \ref gz::sim::Model entity in this
27+
case.
28+
`OdometryPublisher` happens to be a system meant to be specified under `<model>`
29+
in the SDF, so at the time `Configure()` is called, it has access to a model
30+
entity from which we can extract a \ref gz::sim::Model:
31+
32+
\snippet src/systems/odometry_publisher/OdometryPublisher.cc modelDeclaration
33+
\snippet src/systems/odometry_publisher/OdometryPublisher.cc Configure
34+
35+
### Read the pose component
36+
37+
Once we have the handle to an entity, we can access components associated with
38+
it.
39+
A component may have been created at the time the world is loaded, or you may
40+
create a component at runtime if it does not exist yet.
41+
42+
In this case, we use the model entity found above to access its pose component,
43+
which is created by default on every model entity.
44+
45+
In `PostUpdate()`, which happens after physics has updated, we can get the
46+
world pose of a model through gz::sim::worldPose, by passing in the model
47+
entity and the entity component manager.
48+
49+
\snippet src/systems/odometry_publisher/OdometryPublisher.cc worldPose
50+
51+
It returns the raw data to us in the gz::math::Pose3d type, which is also the
52+
data type underlying a pose component.
53+
We can perform calculations on the gz::math::Pose3d type, not the
54+
gz::sim::components::Pose type, which is just a wrapper.
55+
56+
### Use the pose component
57+
58+
Now we can use the pose data as we like.
59+
60+
Here, we manipulate the pose and package the result into a gz::msgs::Odometry
61+
message to be published:
62+
63+
\snippet src/systems/odometry_publisher/OdometryPublisher.cc declarePoseMsg
64+
65+
\snippet src/systems/odometry_publisher/OdometryPublisher.cc setPoseMsg
66+
67+
See the source code for setting other fields of the message, such as twist and
68+
the header.
69+
70+
The message is then published:
71+
72+
\snippet src/systems/odometry_publisher/OdometryPublisher.cc publishMsg
73+
74+
where `odomPub` is defined in `Configure()`:
75+
76+
\snippet src/systems/odometry_publisher/OdometryPublisher.cc definePub
77+
78+
Outside the scope of this tutorial, the odometry publisher system also
79+
calculates the covariance and publishes a pose vector on a TF topic.
80+
See the source code to learn more.

tutorials/using_components.md

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -72,3 +72,4 @@ The rest of the tutorial is case studies that walk through the usage of
7272
specific components.
7373

7474
- \subpage jointforcecmdcomponent "JointForceCmd"
75+
- \subpage posecomponent "Pose"

0 commit comments

Comments
 (0)