|
| 1 | +/* |
| 2 | + * Copyright (C) 2022 Open Source Robotics Foundation |
| 3 | + * |
| 4 | + * Licensed under the Apache License, Version 2.0 (the "License"); |
| 5 | + * you may not use this file except in compliance with the License. |
| 6 | + * You may obtain a copy of the License at |
| 7 | + * |
| 8 | + * http://www.apache.org/licenses/LICENSE-2.0 |
| 9 | + * |
| 10 | + * Unless required by applicable law or agreed to in writing, software |
| 11 | + * distributed under the License is distributed on an "AS IS" BASIS, |
| 12 | + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 13 | + * See the License for the specific language governing permissions and |
| 14 | + * limitations under the License. |
| 15 | + * |
| 16 | + */ |
| 17 | + |
| 18 | +#include <gtest/gtest.h> |
| 19 | +#include <ignition/common/Console.hh> |
| 20 | +#include <ignition/common/Util.hh> |
| 21 | +#include <ignition/math/Pose3.hh> |
| 22 | +#include <ignition/transport/Node.hh> |
| 23 | +#include <ignition/utilities/ExtraTestMacros.hh> |
| 24 | + |
| 25 | +#include "ignition/gazebo/components/Name.hh" |
| 26 | +#include "ignition/gazebo/components/Model.hh" |
| 27 | +#include "ignition/gazebo/components/Pose.hh" |
| 28 | +#include "ignition/gazebo/Server.hh" |
| 29 | +#include "ignition/gazebo/SystemLoader.hh" |
| 30 | +#include "ignition/gazebo/test_config.hh" |
| 31 | + |
| 32 | +#include "../helpers/EnvTestFixture.hh" |
| 33 | +#include "../helpers/Relay.hh" |
| 34 | + |
| 35 | +using namespace ignition; |
| 36 | +using namespace gazebo; |
| 37 | +using namespace std::chrono_literals; |
| 38 | + |
| 39 | +/// \brief Test DiffDrive system |
| 40 | +class EntitySystemTest : public InternalFixture<::testing::TestWithParam<int>> |
| 41 | +{ |
| 42 | + /// \param[in] _sdfFile SDF file to load. |
| 43 | + /// \param[in] _cmdVelTopic Command velocity topic. |
| 44 | + protected: void TestPublishCmd(const std::string &_sdfFile, |
| 45 | + const std::string &_cmdVelTopic) |
| 46 | + { |
| 47 | + // Start server |
| 48 | + ServerConfig serverConfig; |
| 49 | + serverConfig.SetSdfFile(_sdfFile); |
| 50 | + |
| 51 | + Server server(serverConfig); |
| 52 | + EXPECT_FALSE(server.Running()); |
| 53 | + EXPECT_FALSE(*server.Running(0)); |
| 54 | + |
| 55 | + Entity vehicleEntity = kNullEntity; |
| 56 | + |
| 57 | + // Create a system that records the vehicle poses |
| 58 | + test::Relay testSystem; |
| 59 | + |
| 60 | + std::vector<math::Pose3d> poses; |
| 61 | + testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &, |
| 62 | + const gazebo::EntityComponentManager &_ecm) |
| 63 | + { |
| 64 | + auto id = _ecm.EntityByComponents( |
| 65 | + components::Model(), |
| 66 | + components::Name("vehicle")); |
| 67 | + EXPECT_NE(kNullEntity, id); |
| 68 | + vehicleEntity = id; |
| 69 | + |
| 70 | + auto poseComp = _ecm.Component<components::Pose>(id); |
| 71 | + ASSERT_NE(nullptr, poseComp); |
| 72 | + |
| 73 | + poses.push_back(poseComp->Data()); |
| 74 | + }); |
| 75 | + server.AddSystem(testSystem.systemPtr); |
| 76 | + |
| 77 | + // Run server and check that vehicle didn't move |
| 78 | + server.Run(true, 1000, false); |
| 79 | + EXPECT_EQ(1000u, poses.size()); |
| 80 | + |
| 81 | + for (const auto &pose : poses) |
| 82 | + { |
| 83 | + EXPECT_EQ(poses[0], pose); |
| 84 | + } |
| 85 | + poses.clear(); |
| 86 | + |
| 87 | + // Publish command and check that vehicle still does not move |
| 88 | + transport::Node node; |
| 89 | + auto pub = node.Advertise<msgs::Twist>(_cmdVelTopic); |
| 90 | + msgs::Twist msg; |
| 91 | + const double desiredLinVel = 10.5; |
| 92 | + msgs::Set(msg.mutable_linear(), |
| 93 | + math::Vector3d(desiredLinVel, 0, 0)); |
| 94 | + msgs::Set(msg.mutable_angular(), |
| 95 | + math::Vector3d(0.0, 0, 0)); |
| 96 | + pub.Publish(msg); |
| 97 | + server.Run(true, 1000, false); |
| 98 | + for (const auto &pose : poses) |
| 99 | + { |
| 100 | + EXPECT_EQ(poses[0], pose); |
| 101 | + } |
| 102 | + poses.clear(); |
| 103 | + |
| 104 | + // send request to add diff_drive system |
| 105 | + EXPECT_NE(kNullEntity, vehicleEntity); |
| 106 | + msgs::EntityPlugin_V req; |
| 107 | + auto ent = req.mutable_entity(); |
| 108 | + ent->set_id(vehicleEntity); |
| 109 | + auto plugin = req.add_plugins(); |
| 110 | + plugin->set_name("ignition::gazebo::systems::DiffDrive"); |
| 111 | + plugin->set_filename("ignition-gazebo-diff-drive-system"); |
| 112 | + std::stringstream innerxml; |
| 113 | + innerxml |
| 114 | + << "<left_joint>left_wheel_joint</left_joint>\n" |
| 115 | + << "<right_joint>right_wheel_joint</right_joint>\n" |
| 116 | + << "<wheel_separation>1.25</wheel_separation>\n" |
| 117 | + << "<wheel_radius>0.3</wheel_radius>\n" |
| 118 | + << "<max_linear_acceleration>1</max_linear_acceleration>\n" |
| 119 | + << "<min_linear_acceleration>-1</min_linear_acceleration>\n" |
| 120 | + << "<max_angular_acceleration>2</max_angular_acceleration>\n" |
| 121 | + << "<min_angular_acceleration>-2</min_angular_acceleration>\n" |
| 122 | + << "<max_linear_velocity>0.5</max_linear_velocity>\n" |
| 123 | + << "<min_linear_velocity>-0.5</min_linear_velocity>\n" |
| 124 | + << "<max_angular_velocity>1</max_angular_velocity>\n" |
| 125 | + << "<min_angular_velocity>-1</min_angular_velocity>\n"; |
| 126 | + plugin->set_innerxml(innerxml.str()); |
| 127 | + |
| 128 | + msgs::Boolean res; |
| 129 | + bool result; |
| 130 | + unsigned int timeout = 5000; |
| 131 | + std::string service{"/world/diff_drive/entity/system/add"}; |
| 132 | + |
| 133 | + EXPECT_TRUE(node.Request(service, req, timeout, res, result)); |
| 134 | + EXPECT_TRUE(result); |
| 135 | + EXPECT_TRUE(res.data()); |
| 136 | + |
| 137 | + // run once for the system to be added |
| 138 | + server.Run(true, 1, false); |
| 139 | + poses.clear(); |
| 140 | + |
| 141 | + // publish twist msg and verify that the vehicle now moves forward |
| 142 | + pub.Publish(msg); |
| 143 | + server.Run(true, 1000, false); |
| 144 | + for (unsigned int i = 1; i < poses.size(); ++i) |
| 145 | + { |
| 146 | + EXPECT_GT(poses[i].Pos().X(), poses[i-1].Pos().X()); |
| 147 | + } |
| 148 | + } |
| 149 | +}; |
| 150 | + |
| 151 | +///////////////////////////////////////////////// |
| 152 | +// See https://github.com/gazebosim/gz-sim/issues/1175 |
| 153 | +TEST_P(EntitySystemTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(PublishCmd)) |
| 154 | +{ |
| 155 | + TestPublishCmd( |
| 156 | + std::string(PROJECT_SOURCE_PATH) + |
| 157 | + "/test/worlds/diff_drive_no_plugin.sdf", |
| 158 | + "/model/vehicle/cmd_vel"); |
| 159 | +} |
| 160 | + |
| 161 | +// Run multiple times |
| 162 | +INSTANTIATE_TEST_SUITE_P(ServerRepeat, EntitySystemTest, |
| 163 | + ::testing::Range(1, 2)); |
0 commit comments