diff --git a/examples/worlds/boundingbox_camera.sdf b/examples/worlds/boundingbox_camera.sdf index a4c16af4c5f..eb7c7afd86e 100644 --- a/examples/worlds/boundingbox_camera.sdf +++ b/examples/worlds/boundingbox_camera.sdf @@ -5,20 +5,20 @@ + filename="gz-sim-physics-system" + name="gz::sim::systems::Physics"> + filename="gz-sim-user-commands-system" + name="gz::sim::systems::UserCommands"> + filename="gz-sim-scene-broadcaster-system" + name="gz::sim::systems::SceneBroadcaster"> + filename="gz-sim-sensors-system" + name="gz::sim::systems::Sensors"> ogre2 @@ -26,11 +26,11 @@ - + 3D View false docked - + ogre2 scene @@ -41,43 +41,43 @@ - + floating 5 5 false - + - + false 5 5 floating false - + - + false 5 5 floating false - + - + false 5 5 floating false - + - + World control false false @@ -90,7 +90,7 @@ - + true true @@ -101,7 +101,7 @@ - + World stats false false @@ -114,7 +114,7 @@ - + true true @@ -124,32 +124,32 @@ boxes_full_2d_image - + Full 2D docked 400 600 - + boxes_visible_2d_image - + Visible 2D docked 400 600 - + boxes_3d_image - + 3D docked 400 600 - + @@ -228,7 +228,7 @@ 0 0 1 1 0 0 0.3 1 - + @@ -236,7 +236,7 @@ - + 0 1 0.5 0 0 0 @@ -300,7 +300,7 @@ false - + @@ -405,7 +405,7 @@ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Construction Cone - + diff --git a/examples/worlds/multicopter_velocity_control.sdf b/examples/worlds/multicopter_velocity_control.sdf index 689793272b7..5092471ecaa 100644 --- a/examples/worlds/multicopter_velocity_control.sdf +++ b/examples/worlds/multicopter_velocity_control.sdf @@ -18,7 +18,7 @@ You can use the velocity controller and command linear velocity and yaw angular Listen to poses: - ign topic -e -t "/model/x3/pose" + gz topic -e -t "/model/x3/pose" Send commands to the hexacopter to go straight up: diff --git a/src/gz_TEST.cc b/src/gz_TEST.cc index e343c2d2d7a..633b837ad8a 100644 --- a/src/gz_TEST.cc +++ b/src/gz_TEST.cc @@ -171,15 +171,15 @@ TEST(CmdLine, GZ_UTILS_TEST_DISABLED_ON_WIN32(ResourcePath)) TEST(CmdLine, GZ_UTILS_TEST_DISABLED_ON_WIN32(GazeboHelpVsCompletionFlags)) { // Flags in help message - std::string helpOutput = customExecStr(kGzCommand + " gazebo --help"); + std::string helpOutput = customExecStr(kGzCommand + " sim --help"); // Call the output function in the bash completion script std::string scriptPath = gz::common::joinPaths( std::string(PROJECT_SOURCE_PATH), - "src", "cmd", "gazebo.bash_completion.sh"); + "src", "cmd", "sim.bash_completion.sh"); // Equivalent to: - // sh -c "bash -c \". /path/to/gazebo.bash_completion.sh; _gz_sim_flags\"" + // sh -c "bash -c \". /path/to/sim.bash_completion.sh; _gz_sim_flags\"" std::string cmd = "bash -c \". " + scriptPath + "; _gz_sim_flags\""; std::string scriptOutput = customExecStr(cmd); @@ -193,7 +193,7 @@ TEST(CmdLine, GZ_UTILS_TEST_DISABLED_ON_WIN32(GazeboHelpVsCompletionFlags)) // Match each flag in script output with help message for (const auto &flag : flags) { - EXPECT_NE(std::string::npos, helpOutput.find(flag)) << helpOutput; + EXPECT_NE(std::string::npos, helpOutput.find(flag)) << flag; } } diff --git a/src/systems/odometry_publisher/OdometryPublisher.cc b/src/systems/odometry_publisher/OdometryPublisher.cc index c6f29d9b965..b9d4e09369b 100644 --- a/src/systems/odometry_publisher/OdometryPublisher.cc +++ b/src/systems/odometry_publisher/OdometryPublisher.cc @@ -233,7 +233,7 @@ void OdometryPublisher::Configure(const Entity &_entity, { this->dataPtr->odomPub = this->dataPtr->node.Advertise( odomTopicValid); - ignmsg << "OdometryPublisher publishing odometry on [" << odomTopicValid + gzmsg << "OdometryPublisher publishing odometry on [" << odomTopicValid << "]" << std::endl; } @@ -248,25 +248,24 @@ void OdometryPublisher::Configure(const Entity &_entity, { this->dataPtr->odomCovPub = this->dataPtr->node.Advertise< msgs::OdometryWithCovariance>(odomCovTopicValid); - ignmsg << "OdometryPublisher publishing odometry with covariance on [" + gzmsg << "OdometryPublisher publishing odometry with covariance on [" << odomCovTopicValid << "]" << std::endl; } - std::string tfTopic{"/model/" + this->dataPtr->model.Name(_ecm) + - "/pose"}; + std::string tfTopic{"/model/" + this->dataPtr->model.Name(_ecm) + "/pose"}; if (_sdf->HasElement("tf_topic")) tfTopic = _sdf->Get("tf_topic"); std::string tfTopicValid {transport::TopicUtils::AsValidTopic(tfTopic)}; if (tfTopicValid.empty()) { - ignerr << "Failed to generate valid TF topic from [" << tfTopic << "]" + gzerr << "Failed to generate valid TF topic from [" << tfTopic << "]" << std::endl; } else { this->dataPtr->tfPub = this->dataPtr->node.Advertise( tfTopicValid); - ignmsg << "OdometryPublisher publishing Pose_V (TF) on [" + gzmsg << "OdometryPublisher publishing Pose_V (TF) on [" << tfTopicValid << "]" << std::endl; } } diff --git a/tutorials/resources.md b/tutorials/resources.md index 67b772d3ec8..ffcb19e9778 100644 --- a/tutorials/resources.md +++ b/tutorials/resources.md @@ -111,9 +111,7 @@ Top-level entities such as models, lights and actors may be loaded through: * Path / URL to SDF file * (TODO) `gz::msgs::Model`, `gz::msgs::Light` * Within a system, using -==== BASE ==== [SdfEntityCreator](https://ignitionrobotics.org/api/gazebo/4.6/classignition_1_1gazebo_1_1SdfEntityCreator.html) -==== BASE ==== or directly creating components and entities. Gazebo will look for URIs (path / URL) in the following, in order: