diff --git a/examples/worlds/drive_to_pose_controller.sdf b/examples/worlds/drive_to_pose_controller.sdf
index e9342cd2d4..8da20faf98 100644
--- a/examples/worlds/drive_to_pose_controller.sdf
+++ b/examples/worlds/drive_to_pose_controller.sdf
@@ -38,7 +38,7 @@
gz topic -t "/model/DeliveryBot/cmd_pose" -m gz.msgs.Pose_V \
-p "pose:[{position: {x: -5.9, y: 9.18, z: 0.0}, orientation: {x: 0.0, y: 0.0, z: 0.99, w: 0.0}}]"
- This plugin is loosely base on the control schemes introduced in Chapter 4 (pp. 130-142) of
+ This plugin is loosely based on the control schemes introduced in Chapter 4 (pp. 130-142) of
Robotics, Vision and Control by Corke, Jachimczyk and Pillat and it can be found at:
https://link.springer.com/chapter/10.1007/978-3-031-07262-8_4
@@ -153,7 +153,6 @@
name="gz::sim::systems::Physics">
-
https://fuel.gazebosim.org/1.0/OpenRobotics/models/aws_robomaker_warehouse_ShelfF_01
@@ -222,7 +221,6 @@
0 0 -4 0 0 0
-
https://fuel.gazebosim.org/1.0/OpenRobotics/models/aws_robomaker_warehouse_Bucket_01
@@ -265,7 +263,6 @@
-1.491287 5.222435 -0.017477 0 0 -1.583185
-
https://fuel.gazebosim.org/1.0/OpenRobotics/models/aws_robomaker_warehouse_ClutteringC_01
@@ -322,7 +319,6 @@
-1.592441 7.715420 0 0 0 0
-
0 0 8.5 0 0 0
0.5 0.5 0.5 1
diff --git a/src/systems/drive_to_pose_controller/DriveToPoseController.hh b/src/systems/drive_to_pose_controller/DriveToPoseController.hh
index 932e917bc2..b61d62ed47 100644
--- a/src/systems/drive_to_pose_controller/DriveToPoseController.hh
+++ b/src/systems/drive_to_pose_controller/DriveToPoseController.hh
@@ -40,7 +40,7 @@ namespace systems
class DriveToPoseControllerPrivate;
/// \brief DriveToPoseController is a simple proportional controller that
- /// is attached to a model to move it in the y giving a pose in Gazebo's
+ /// is attached to a model to move it by giving a pose in Gazebo's
/// world coordinate system. This is not a standalone plugin, and requires
/// the DiffDrive and OdometryPublisher plugins respectively.
///
diff --git a/test/integration/drive_to_pose_controller_system.cc b/test/integration/drive_to_pose_controller_system.cc
index 60b70d9eaa..cd64f92a69 100644
--- a/test/integration/drive_to_pose_controller_system.cc
+++ b/test/integration/drive_to_pose_controller_system.cc
@@ -136,7 +136,7 @@ TEST_F(DriveToPoseControllerTest, CurrentPosePublish)
TestPublishCmd(
gz::common::joinPaths(
std::string(PROJECT_SOURCE_PATH),
- "/test/worlds/drive_to_pose_controller.sdf"),
+ "test", "worlds", "drive_to_pose_controller.sdf"),
"/model/DeliveryBot",
pose);
}
@@ -149,7 +149,7 @@ TEST_F(DriveToPoseControllerTest, XCoordinatePublish)
TestPublishCmd(
gz::common::joinPaths(
std::string(PROJECT_SOURCE_PATH),
- "/test/worlds/drive_to_pose_controller.sdf"),
+ "test", "worlds", "drive_to_pose_controller.sdf"),
"/model/DeliveryBot",
pose);
}
@@ -162,7 +162,7 @@ TEST_F(DriveToPoseControllerTest, YCoordinatePublish)
TestPublishCmd(
gz::common::joinPaths(
std::string(PROJECT_SOURCE_PATH),
- "/test/worlds/drive_to_pose_controller.sdf"),
+ "test", "worlds", "drive_to_pose_controller.sdf"),
"/model/DeliveryBot",
pose);
}
@@ -175,7 +175,7 @@ TEST_F(DriveToPoseControllerTest, YawPublish)
TestPublishCmd(
gz::common::joinPaths(
std::string(PROJECT_SOURCE_PATH),
- "/test/worlds/drive_to_pose_controller.sdf"),
+ "test", "worlds", "drive_to_pose_controller.sdf"),
"/model/DeliveryBot",
pose);
}
@@ -188,7 +188,8 @@ TEST_F(DriveToPoseControllerTest, XYCoordinateYawPublish)
TestPublishCmd(
gz::common::joinPaths(
std::string(PROJECT_SOURCE_PATH),
- "/test/worlds/drive_to_pose_controller.sdf"),
+ "test", "worlds", "drive_to_pose_controller.sdf"),
"/model/DeliveryBot",
pose);
}
+