Skip to content

Commit 7870ccd

Browse files
committed
consistent formatting, units, alignment
Signed-off-by: Louise Poubel <louise@openrobotics.org>
1 parent f36e6b2 commit 7870ccd

3 files changed

Lines changed: 58 additions & 57 deletions

File tree

examples/angle_example.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,7 @@
1616
# installed.
1717
#
1818
# Modify the PYTHONPATH environment variable to include the ignition math
19-
# library install path. For example, if you install to /user:
19+
# library install path. For example, if you install to /usr:
2020
#
2121
# $ export PYTHONPATH=/usr/lib/python:$PYTHONPATH
2222
#

examples/diff_drive_odometry.cc

Lines changed: 26 additions & 32 deletions
Original file line numberDiff line numberDiff line change
@@ -36,66 +36,60 @@ int main(int argc, char **argv)
3636
// This is the linear distance traveled per degree of wheel rotation.
3737
double distPerDegree = wheelCircumference / 360.0;
3838

39+
// Setup the wheel parameters, and initialize
3940
odom.SetWheelParams(wheelSeparation, wheelRadius, wheelRadius);
4041
auto startTime = std::chrono::steady_clock::now();
4142
odom.Init(startTime);
4243

4344
// Sleep for a little while, then update the odometry with the new wheel
4445
// position.
45-
std::cout << "--- Rotate the both wheels by 1 degree. ---" << '\n';
46+
std::cout << "--- Rotate both wheels by 1 degree. ---" << '\n';
4647
auto time1 = startTime + std::chrono::milliseconds(100);
4748
odom.Update(IGN_DTOR(1.0), IGN_DTOR(1.0), time1);
4849

49-
// Linear velocity should be dist_traveled / time_elapsed.
50-
std::cout << "\tLinear velocity: " << distPerDegree / 0.1
51-
<< " Odom linear velocity: " << odom.LinearVelocity() << std::endl;
50+
std::cout << "\tLinear velocity:\t" << distPerDegree / 0.1 << " m/s"
51+
<< "\n\tOdom linear velocity:\t" << odom.LinearVelocity() << " m/s"
52+
<< std::endl;
5253

53-
// Angular velocity should be zero since the "robot" is traveling in a
54-
// straight line.
55-
std::cout << "Angular velocity should be zero since the 'robot' is traveling"
56-
<< " in a straight line:\n"
57-
<< "\tOdom angular velocity: "
58-
<< *odom.AngularVelocity() << std::endl;
54+
std::cout << "Angular velocity should be zero since the \"robot\" is traveling\n"
55+
<< "in a straight line:\n"
56+
<< "\tOdom angular velocity:\t"
57+
<< *odom.AngularVelocity() << " rad/s" << std::endl;
5958

6059
// Sleep again, this time rotate the right wheel by 1 degree.
6160
std::cout << "--- This time rotate the right wheel by 1 degree. ---"
6261
<< std::endl;
6362
auto time2 = time1 + std::chrono::milliseconds(100);
6463
odom.Update(IGN_DTOR(2.0), IGN_DTOR(3.0), time2);
6564

66-
// The heading should be the arc tangent of the linear distance traveled
67-
// by the right wheel (the left wheel was stationary) divided by the
68-
// wheel separation.
69-
std::cerr << "The heading should be the arc tangent of the linear distance"
70-
<< " traveled by the right wheel (the left wheel was stationary)"
71-
<< " divided by the wheel separation.\n"
72-
<< "\tHeading: " << atan2(distPerDegree, wheelSeparation)
73-
<< " Odom Heading " << *odom.Heading() << '\n';
65+
std::cout << "The heading should be the arc tangent of the linear distance\n"
66+
<< "traveled by the right wheel (the left wheel was stationary)\n"
67+
<< "divided by the wheel separation.\n"
68+
<< "\tHeading:\t\t" << atan2(distPerDegree, wheelSeparation) << " rad"
69+
<< "\n\tOdom Heading:\t\t" << *odom.Heading() << " rad" << '\n';
7470

7571
// The X odom reading should have increased by the sine of the heading *
7672
// half the wheel separation.
7773
double xDistTraveled =
7874
sin(atan2(distPerDegree, wheelSeparation)) * wheelSeparation * 0.5;
7975
double prevXPos = distPerDegree * 2.0;
80-
std::cout << "\tX distance traveled " << xDistTraveled + prevXPos
81-
<< " Odom X: " << odom.X() << std::endl;
76+
std::cout << "\tX distance traveled:\t" << xDistTraveled + prevXPos << " m"
77+
<< "\n\tOdom X:\t\t" << odom.X() << " m" << std::endl;
8278

83-
// The Y odom reading should have increased by the cosine of the header *
79+
// The Y odom reading should have increased by the cosine of the heading *
8480
// half the wheel separation.
8581
double yDistTraveled = (wheelSeparation * 0.5) -
8682
cos(atan2(distPerDegree, wheelSeparation)) * wheelSeparation * 0.5;
8783
double prevYPos = 0.0;
88-
std::cout << "\tY distance traveled " << yDistTraveled + prevYPos
89-
<< " Odom Y: " << odom.Y() << std::endl;
84+
std::cout << "\tY distance traveled:\t" << yDistTraveled + prevYPos << " m"
85+
<< "\n\tOdom Y:\t\t" << odom.Y() << " m" << std::endl;
9086

91-
// Angular velocity should be the difference between the x and y distance
92-
// traveled divided by the wheel separation divided by the seconds
93-
// elapsed.
94-
std::cout << "Angular velocity should be the difference between the x and y"
95-
<< " distance traveled divided by the wheel separation divided by"
96-
<< " the seconds elapsed.\n"
97-
<< "\tAngular velocity "
98-
<< ((xDistTraveled - yDistTraveled) / wheelSeparation) / 0.1
99-
<< " Odom angular velocity: " << *odom.AngularVelocity() << std::endl;
87+
std::cout << "Angular velocity should be the difference between the x and y\n"
88+
<< "distance traveled divided by the wheel separation divided by\n"
89+
<< "the seconds elapsed.\n"
90+
<< "\tAngular velocity:\t"
91+
<< ((xDistTraveled - yDistTraveled) / wheelSeparation) / 0.1 << " rad/s"
92+
<< "\n\tOdom angular velocity:\t" << *odom.AngularVelocity() << " rad/s"
93+
<< std::endl;
10094
}
10195
//! [complete]

examples/diff_drive_odometry.py

Lines changed: 31 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,14 @@
1212
# See the License for the specific language governing permissions and
1313
# limitations under the License.
1414

15+
# This example will only work if the Python interface library was compiled and
16+
# installed.
17+
#
18+
# Modify the PYTHONPATH environment variable to include the ignition math
19+
# library install path. For example, if you install to /usr:
20+
#
21+
# $ export PYTHONPATH=/usr/lib/python:$PYTHONPATH
22+
1523
import datetime
1624
import math
1725

@@ -21,7 +29,7 @@
2129

2230
wheelSeparation = 2.0
2331
wheelRadius = 0.5
24-
wheelCircumference = 2 * 3.1416 * wheelRadius
32+
wheelCircumference = 2 * math.pi * wheelRadius
2533

2634
# This is the linear distance traveled per degree of wheel rotation.
2735
distPerDegree = wheelCircumference / 360.0
@@ -31,31 +39,33 @@
3139
startTime = datetime.datetime.now()
3240
odom.init(datetime.timedelta())
3341

34-
print('--- Rotate the both wheels by 1 degree. ---')
42+
# Sleep for a little while, then update the odometry with the new wheel
43+
# position.
44+
print('--- Rotate both wheels by 1 degree. ---')
3545
time1 = startTime + datetime.timedelta(milliseconds=100)
36-
odom.update(Angle(1.0 * 3.1416 / 180),
37-
Angle(1.0 * 3.1416 / 180),
46+
odom.update(Angle(1.0 * math.pi / 180),
47+
Angle(1.0 * math.pi / 180),
3848
time1 - startTime)
3949

40-
print('Linear velocity: {} Odom linear velocity: {}'.
50+
print('\tLinear velocity:\t{} m/s\n\tOdom linear velocity:\t{} m/s'.
4151
format(distPerDegree / 0.1, odom.linear_velocity()))
4252

43-
print('Angular velocity should be zero since the "robot" is traveling' +
44-
' in a straight line:\n' +
45-
'\tOdom angular velocity: {}'
53+
print('Angular velocity should be zero since the "robot" is traveling\n' +
54+
'in a straight line:\n' +
55+
'\tOdom angular velocity:\t{} rad/s'
4656
.format(odom.angular_velocity()))
4757

4858
# Sleep again, this time rotate the right wheel by 1 degree.
4959
print('--- This time rotate the right wheel by 1 degree. ---');
5060
time2 = time1 + datetime.timedelta(milliseconds=100)
51-
odom.update(Angle(2.0 * 3.1416 / 180),
52-
Angle(3.0 * 3.1416 / 180),
61+
odom.update(Angle(2.0 * math.pi / 180),
62+
Angle(3.0 * math.pi / 180),
5363
time2 - startTime)
5464

55-
print('The heading should be the arc tangent of the linear distance' +
56-
' traveled by the right wheel (the left wheel was stationary)' +
57-
' divided by the wheel separation.\n' +
58-
'\tHeading: {} Odom Heading: {}'.format(
65+
print('The heading should be the arc tangent of the linear distance\n' +
66+
'traveled by the right wheel (the left wheel was stationary)\n' +
67+
'divided by the wheel separation.\n' +
68+
'\tHeading:\t\t{} rad\n\tOdom Heading:\t\t{} rad'.format(
5969
math.atan2(distPerDegree, wheelSeparation),
6070
odom.heading()))
6171

@@ -64,23 +74,20 @@
6474
xDistTraveled = math.sin(
6575
math.atan2(distPerDegree, wheelSeparation)) * wheelSeparation * 0.5
6676
prevXPos = distPerDegree * 2.0
67-
print('\tX distance traveled: {} Odom X: {}'.format(
77+
print('\tX distance traveled:\t{} m\n\tOdom X:\t\t{} m'.format(
6878
xDistTraveled + prevXPos, odom.x()))
6979

70-
# The Y odom reading should have increased by the cosine of the header *
80+
# The Y odom reading should have increased by the cosine of the heading *
7181
# half the wheel separation.
7282
yDistTraveled = (wheelSeparation * 0.5) - math.cos(
7383
math.atan2(distPerDegree, wheelSeparation)) * wheelSeparation * 0.5
7484
prevYPos = 0.0
75-
print('\tY distance traveled: {} Odom Y: {}'.format(
85+
print('\tY distance traveled:\t{} m\n\tOdom Y:\t\t{} m'.format(
7686
yDistTraveled + prevYPos, odom.y()))
7787

78-
# Angular velocity should be the difference between the x and y distance
79-
# traveled divided by the wheel separation divided by the seconds
80-
# elapsed.
81-
print('Angular velocity should be the difference between the x and y' +
82-
' distance traveled divided by the wheel separation divided by' +
83-
' the seconds elapsed.\n' +
84-
'\tAngular velocity: {} Odom angular velocity: {}'.format(
88+
print('Angular velocity should be the difference between the x and y\n' +
89+
'distance traveled divided by the wheel separation divided by\n' +
90+
'the seconds elapsed.\n' +
91+
'\tAngular velocity:\t{} rad/s\n\tOdom angular velocity:\t{} rad/s'.format(
8592
((xDistTraveled - yDistTraveled) / wheelSeparation) / 0.1,
8693
odom.angular_velocity()))

0 commit comments

Comments
 (0)