diff --git a/.gitignore b/.gitignore index aeeb8878..0eaf271b 100644 --- a/.gitignore +++ b/.gitignore @@ -10,3 +10,6 @@ docs/_templates/* */.history **/.idea/ **/cmake-build-debug/ +build +install +log diff --git a/flatland_plugins/src/bumper.cpp b/flatland_plugins/src/bumper.cpp index d2a92156..8e5311ae 100644 --- a/flatland_plugins/src/bumper.cpp +++ b/flatland_plugins/src/bumper.cpp @@ -114,6 +114,9 @@ void Bumper::BeforePhysicsStep(const Timekeeper & timekeeper) for (it = contact_states_.begin(); it != contact_states_.end(); it++) { it->second.Reset(); } + + // Avoid -Wunused-parameter warnings - remove if parameter is used! + (void)timekeeper; } void Bumper::AfterPhysicsStep(const Timekeeper & timekeeper) diff --git a/flatland_plugins/src/diff_drive.cpp b/flatland_plugins/src/diff_drive.cpp index c031ce74..d390bd1b 100644 --- a/flatland_plugins/src/diff_drive.cpp +++ b/flatland_plugins/src/diff_drive.cpp @@ -162,7 +162,7 @@ void DiffDrive::OnInitialize(const YAML::Node & config) "twist_sub(%s) odom_pub(%s) ground_truth_pub(%s) " "odom_pose_noise({%f,%f,%f}) odom_twist_noise({%f,%f,%f}) " "pub_rate(%f)\n", - body_, body_->name_.c_str(), odom_frame_id.c_str(), twist_topic.c_str(), odom_topic.c_str(), + (void*)body_, body_->name_.c_str(), odom_frame_id.c_str(), twist_topic.c_str(), odom_topic.c_str(), ground_truth_topic.c_str(), odom_pose_noise[0], odom_pose_noise[1], odom_pose_noise[2], odom_twist_noise[0], odom_twist_noise[1], odom_twist_noise[2], pub_rate); } diff --git a/flatland_plugins/src/laser.cpp b/flatland_plugins/src/laser.cpp index e93a008e..bb299f89 100644 --- a/flatland_plugins/src/laser.cpp +++ b/flatland_plugins/src/laser.cpp @@ -218,6 +218,10 @@ float LaserCallback::ReportFixture( did_hit_ = true; fraction_ = fraction; + // Avoid -Wunused-parameter warnings - remove if parameter is used! + (void)point; + (void)normal; + return fraction; } @@ -274,7 +278,7 @@ void Laser::ParseParameters(const YAML::Node & config) "frame_id(%s) broadcast_tf(%d) update_rate(%f) range(%f) " "noise_std_dev(%f) angle_min(%f) angle_max(%f) " "angle_increment(%f) layers(0x%u {%s})", - GetName().c_str(), topic_.c_str(), body_name.c_str(), body_, origin_.x, origin_.y, + GetName().c_str(), topic_.c_str(), body_name.c_str(), (void*)body_, origin_.x, origin_.y, origin_.theta, frame_id_.c_str(), broadcast_tf_, update_rate_, range_, noise_std_dev_, min_angle_, max_angle_, increment_, layers_bits_, boost::algorithm::join(layers, ",").c_str()); } diff --git a/flatland_plugins/src/model_tf_publisher.cpp b/flatland_plugins/src/model_tf_publisher.cpp index 03b1e42f..ef7dfe2e 100644 --- a/flatland_plugins/src/model_tf_publisher.cpp +++ b/flatland_plugins/src/model_tf_publisher.cpp @@ -102,7 +102,7 @@ void ModelTfPublisher::OnInitialize(const YAML::Node & config) rclcpp::get_logger("ModelTFPublisher"), "Initialized with params: reference(%s, %p) " "publish_tf_world(%d) world_frame_id(%s) update_rate(%f), exclude({%s})", - reference_body_->name_.c_str(), reference_body_, publish_tf_world_, world_frame_id_.c_str(), + reference_body_->name_.c_str(), (void*)reference_body_, publish_tf_world_, world_frame_id_.c_str(), update_rate_, boost::algorithm::join(excluded_body_names, ",").c_str()); } diff --git a/flatland_plugins/src/tricycle_drive.cpp b/flatland_plugins/src/tricycle_drive.cpp index 770d0330..5cd095e5 100644 --- a/flatland_plugins/src/tricycle_drive.cpp +++ b/flatland_plugins/src/tricycle_drive.cpp @@ -174,8 +174,8 @@ void TricycleDrive::OnInitialize(const YAML::Node & config) "odom_frame_id(%s) twist_sub(%s) odom_pub(%s) " "ground_truth_pub(%s) odom_pose_noise({%f,%f,%f}) " "odom_twist_noise({%f,%f,%f}) pub_rate(%f)\n", - body_, body_->GetName().c_str(), front_wj_, front_wj_->GetName().c_str(), rear_left_wj_, - rear_left_wj_->GetName().c_str(), rear_right_wj_, rear_right_wj_->GetName().c_str(), + (void*)body_, body_->GetName().c_str(), (void*)front_wj_, front_wj_->GetName().c_str(), (void*)rear_left_wj_, + rear_left_wj_->GetName().c_str(), (void*)rear_right_wj_, rear_right_wj_->GetName().c_str(), odom_frame_id.c_str(), twist_topic.c_str(), odom_topic.c_str(), ground_truth_topic.c_str(), odom_pose_noise[0], odom_pose_noise[1], odom_pose_noise[2], odom_twist_noise[0], odom_twist_noise[1], odom_twist_noise[2], pub_rate); diff --git a/flatland_plugins/src/tween.cpp b/flatland_plugins/src/tween.cpp index afb97fcb..bf965766 100644 --- a/flatland_plugins/src/tween.cpp +++ b/flatland_plugins/src/tween.cpp @@ -242,7 +242,7 @@ void Tween::OnInitialize(const YAML::Node & config) "duration %f " "mode: %s [%d] " "easing: %s\n", - body_, body_->name_.c_str(), start_.x, start_.y, start_.theta, delta_.x, delta_.y, delta_.theta, + (void*)body_, body_->name_.c_str(), start_.x, start_.y, start_.theta, delta_.x, delta_.y, delta_.theta, duration_, mode.c_str(), (int)mode_, easing.c_str()); } diff --git a/flatland_plugins/src/world_modifier.cpp b/flatland_plugins/src/world_modifier.cpp index 6a20cc43..59724694 100644 --- a/flatland_plugins/src/world_modifier.cpp +++ b/flatland_plugins/src/world_modifier.cpp @@ -78,6 +78,11 @@ float RayTrace::ReportFixture( } is_hit_ = true; fraction_ = fraction; + + // Avoid -Wunused-parameter warnings - remove if parameter is used! + (void)point; + (void)normal; + return fraction; } diff --git a/flatland_plugins/src/world_random_wall.cpp b/flatland_plugins/src/world_random_wall.cpp index dcf6239b..84dde635 100644 --- a/flatland_plugins/src/world_random_wall.cpp +++ b/flatland_plugins/src/world_random_wall.cpp @@ -54,6 +54,7 @@ #include #include #include +#include #include #include @@ -113,8 +114,9 @@ void RandomWall::OnInitialize(const YAML::Node & config, YamlReader & world_conf for (b2Fixture * f = layer->body_->physics_body_->GetFixtureList(); f; f = f->GetNext()) { Wall_List.push_back(static_cast(f->GetShape())); } - std::srand(std::time(0)); - std::random_shuffle(Wall_List.begin(), Wall_List.end()); + auto rd = std::random_device {}; + auto rng = std::default_random_engine { rd() }; + std::shuffle(Wall_List.begin(), Wall_List.end(), rng); try { for (unsigned int i = 0; i < num_of_walls; i++) { modifier.AddFullWall(Wall_List[i]); diff --git a/flatland_plugins/test/laser_test.cpp b/flatland_plugins/test/laser_test.cpp index 04997a77..8b2fa423 100644 --- a/flatland_plugins/test/laser_test.cpp +++ b/flatland_plugins/test/laser_test.cpp @@ -64,6 +64,7 @@ class LaserPluginTest : public ::testing::Test boost::filesystem::path this_file_dir; boost::filesystem::path world_yaml; sensor_msgs::msg::LaserScan scan_front, scan_center, scan_back; + bool scan_front_received, scan_center_received, scan_back_received; World * w; std::shared_ptr node; @@ -73,6 +74,9 @@ class LaserPluginTest : public ::testing::Test { this_file_dir = boost::filesystem::path(__FILE__).parent_path(); w = nullptr; + scan_front_received = false; + scan_center_received = false; + scan_back_received = false; } void TearDown() override { delete w; } @@ -117,18 +121,47 @@ class LaserPluginTest : public ::testing::Test float angle_max, float angle_increment, float time_increment, float scan_time, float range_min, float range_max, std::vector ranges, std::vector intensities) { + bool return_value = true; if (scan.header.frame_id != frame_id) { printf("frame_id Actual:%s != Expected:%s\n", scan.header.frame_id.c_str(), frame_id.c_str()); - return false; + return_value = false; + } + + if (!FloatEq("angle_min", scan.angle_min, angle_min)) { + printf("angle_min Actual: %f != Expected: %f\n", scan.angle_min, angle_min); + return_value = false; + } + + if (!FloatEq("angle_max", scan.angle_max, angle_max)) { + printf("angle_max Actual: %f != Expected: %f\n", scan.angle_max, angle_max); + return_value = false; + } + + if (!FloatEq("angle_increment", scan.angle_increment, angle_increment)) { + printf("angle_increment Actual: %f != Expected: %f\n", scan.angle_increment, angle_increment); + return_value = false; + } + + if (!FloatEq("time_increment", scan.time_increment, time_increment)) { + printf("time_increment Actual: %f != Expected: %f\n", scan.time_increment, time_increment); + return_value = false; + } + + if (!FloatEq("scan_time", scan.scan_time, scan_time)) { + printf("scan_time Actual: %f != Expected: %f\n", scan.scan_time, scan_time); + return_value = false; + } + + if (!FloatEq("range_min", scan.range_min, range_min)) { + printf("range_min Actual: %f != Expected: %f\n", scan.range_min, range_min); + return_value = false; + } + + if (!FloatEq("range_max", scan.range_max, range_max)) { + printf("range_max Actual: %f != Expected: %f\n", scan.range_max, range_max); + return_value = false; } - if (!FloatEq("angle_min", scan.angle_min, angle_min)) return false; - if (!FloatEq("angle_max", scan.angle_max, angle_max)) return false; - if (!FloatEq("angle_increment", scan.angle_increment, angle_increment)) return false; - if (!FloatEq("time_increment", scan.time_increment, time_increment)) return false; - if (!FloatEq("scan_time", scan.scan_time, scan_time)) return false; - if (!FloatEq("range_min", scan.range_min, range_min)) return false; - if (!FloatEq("range_max", scan.range_max, range_max)) return false; if ( ranges.size() != scan.ranges.size() || @@ -140,7 +173,7 @@ class LaserPluginTest : public ::testing::Test printf("Expected: "); print_flt_vec(ranges); printf("\n"); - return false; + return_value = false; } if ( @@ -153,15 +186,27 @@ class LaserPluginTest : public ::testing::Test printf("Expected: "); print_flt_vec(intensities); printf("\n"); - return false; + return_value = false; } - return true; + return return_value; } - void ScanFrontCb(const sensor_msgs::msg::LaserScan & msg) { scan_front = msg; }; - void ScanCenterCb(const sensor_msgs::msg::LaserScan & msg) { scan_center = msg; }; - void ScanBackCb(const sensor_msgs::msg::LaserScan & msg) { scan_back = msg; }; + void ScanFrontCb(const sensor_msgs::msg::LaserScan & msg) { + scan_front = msg; + scan_front_received = true; + }; + + void ScanCenterCb(const sensor_msgs::msg::LaserScan & msg) { + scan_center = msg; + scan_center_received = true; + }; + + void ScanBackCb(const sensor_msgs::msg::LaserScan & msg) { + scan_back = msg; + scan_back_received = true; + }; + }; /** @@ -178,11 +223,11 @@ TEST_F(LaserPluginTest, range_test) auto * obj = dynamic_cast(this); auto sub_1 = node->create_subscription( - "scan", 1, std::bind(&LaserPluginTest::ScanFrontCb, obj, _1)); + "robot1/scan", 1, std::bind(&LaserPluginTest::ScanFrontCb, obj, _1)); auto sub_2 = node->create_subscription( - "scan_center", 1, std::bind(&LaserPluginTest::ScanCenterCb, obj, _1)); + "robot1/scan_center", 1, std::bind(&LaserPluginTest::ScanCenterCb, obj, _1)); auto sub_3 = node->create_subscription( - "scan_back", 1, std::bind(&LaserPluginTest::ScanBackCb, obj, _1)); + "robot1/scan_back", 1, std::bind(&LaserPluginTest::ScanBackCb, obj, _1)); auto * p1 = dynamic_cast(w->plugin_manager_.model_plugins_[0].get()); auto * p2 = dynamic_cast(w->plugin_manager_.model_plugins_[1].get()); @@ -190,13 +235,16 @@ TEST_F(LaserPluginTest, range_test) // let it spin for 10 times to make sure the message gets through rclcpp::WallRate rate(500); - for (unsigned int i = 0; i < 10; i++) { + for (unsigned int i = 0; i < 100 && (!scan_front_received || + !scan_center_received || + !scan_back_received); i++) { w->Update(timekeeper); rclcpp::spin_some(node); rate.sleep(); } // check scan returns + EXPECT_TRUE(scan_front_received); EXPECT_TRUE(ScanEq( scan_front, "r_laser_front", -M_PI / 2, M_PI / 2, M_PI / 2, 0.0, 0.0, 0.0, 5.0, {4.5, 4.4, 4.3}, {})); @@ -204,12 +252,14 @@ TEST_F(LaserPluginTest, range_test) << "Actual: " << p1->update_rate_; EXPECT_EQ(p1->body_, w->models_[0]->bodies_[0]); + EXPECT_TRUE(scan_center_received); EXPECT_TRUE(ScanEq( scan_center, "r_center_laser", 0, 2 * M_PI, M_PI / 2, 0.0, 0.0, 0.0, 5.0, {4.8, 4.7, 4.6, 4.9, 4.8}, {})); EXPECT_TRUE(fltcmp(p2->update_rate_, 5000)) << "Actual: " << p2->update_rate_; EXPECT_EQ(p2->body_, w->models_[0]->bodies_[0]); + EXPECT_TRUE(scan_back_received); EXPECT_TRUE(ScanEq( scan_back, "r_laser_back", 0, 2 * M_PI, M_PI / 2, 0.0, 0.0, 0.0, 4, {NAN, 3.2, 3.5, NAN, NAN}, {})); @@ -230,11 +280,11 @@ TEST_F(LaserPluginTest, intensity_test) auto * obj = dynamic_cast(this); auto sub_1 = node->create_subscription( - "scan", 1, std::bind(&LaserPluginTest::ScanFrontCb, obj, _1)); + "robot1/scan", 1, std::bind(&LaserPluginTest::ScanFrontCb, obj, _1)); auto sub_2 = node->create_subscription( - "scan_center", 1, std::bind(&LaserPluginTest::ScanCenterCb, obj, _1)); + "robot1/scan_center", 1, std::bind(&LaserPluginTest::ScanCenterCb, obj, _1)); auto sub_3 = node->create_subscription( - "scan_back", 1, std::bind(&LaserPluginTest::ScanBackCb, obj, _1)); + "robot1/scan_back", 1, std::bind(&LaserPluginTest::ScanBackCb, obj, _1)); auto * p1 = dynamic_cast(w->plugin_manager_.model_plugins_[0].get()); auto * p2 = dynamic_cast(w->plugin_manager_.model_plugins_[1].get()); diff --git a/flatland_plugins/test/laser_tests/intensity_test/robot.model.yaml b/flatland_plugins/test/laser_tests/intensity_test/robot.model.yaml index baa32c38..7da3e5ad 100644 --- a/flatland_plugins/test/laser_tests/intensity_test/robot.model.yaml +++ b/flatland_plugins/test/laser_tests/intensity_test/robot.model.yaml @@ -20,7 +20,7 @@ plugins: - type: Laser name: laser_center - topic: /scan_center + topic: scan_center frame: center_laser body: base_link origin: [0, 0, 0] diff --git a/flatland_plugins/test/laser_tests/range_test/robot.model.yaml b/flatland_plugins/test/laser_tests/range_test/robot.model.yaml index 3338850f..84f16765 100644 --- a/flatland_plugins/test/laser_tests/range_test/robot.model.yaml +++ b/flatland_plugins/test/laser_tests/range_test/robot.model.yaml @@ -20,7 +20,7 @@ plugins: - type: Laser name: laser_center - topic: /scan_center + topic: scan_center frame: center_laser body: base_link origin: [0, 0, 0] diff --git a/flatland_plugins/test/update_timer_test.cpp b/flatland_plugins/test/update_timer_test.cpp index 84bd38f5..513c2d74 100644 --- a/flatland_plugins/test/update_timer_test.cpp +++ b/flatland_plugins/test/update_timer_test.cpp @@ -67,6 +67,9 @@ class TestPlugin : public ModelPlugin { update_timer_.SetRate(0); update_counter_ = 0; + + // Avoid -Wunused-parameter warnings - remove if parameter is used! + (void)config; } void BeforePhysicsStep(const Timekeeper & timekeeper) override diff --git a/flatland_server/include/flatland_server/model.h b/flatland_server/include/flatland_server/model.h index 1d0974ad..f7433a67 100644 --- a/flatland_server/include/flatland_server/model.h +++ b/flatland_server/include/flatland_server/model.h @@ -72,8 +72,8 @@ class Model : public Entity std::string namespace_; ///< namespace of the model std::vector bodies_; ///< list of bodies in the model std::vector joints_; ///< list of joints in the model - YamlReader plugins_reader_; ///< for storing plugins when paring YAML CollisionFilterRegistry * cfr_; ///< Collision filter registry + YamlReader plugins_reader_; ///< for storing plugins when paring YAML std::string viz_name_; ///< used for visualization /** diff --git a/flatland_server/include/flatland_server/world.h b/flatland_server/include/flatland_server/world.h index ee2e02b3..e3cc3b62 100644 --- a/flatland_server/include/flatland_server/world.h +++ b/flatland_server/include/flatland_server/world.h @@ -80,9 +80,9 @@ class World : public b2ContactListener std::vector layers_; ///< list of layers std::vector models_; ///< list of models CollisionFilterRegistry cfr_; ///< collision registry for layers and models - PluginManager plugin_manager_; ///< for loading and updating plugins bool service_paused_; ///< indicates if simulation is paused by a service /// call or not + PluginManager plugin_manager_; ///< for loading and updating plugins InteractiveMarkerManager int_marker_manager_; ///< for dynamically moving models from Rviz int physics_position_iterations_; ///< Box2D solver param int physics_velocity_iterations_; ///< Box2D solver param diff --git a/flatland_server/src/body.cpp b/flatland_server/src/body.cpp index dec08bf1..2aa45c4d 100644 --- a/flatland_server/src/body.cpp +++ b/flatland_server/src/body.cpp @@ -103,8 +103,8 @@ void Body::DebugOutput() const "Body %p: entity(%p, %s) name(%s) color(%f,%f,%f,%f) " "physics_body(%p) num_fixtures(%d) type(%d) pose(%f, %f, %f) " "angular_damping(%f) linear_damping(%f)", - this, entity_, entity_->name_.c_str(), name_.c_str(), color_.r, color_.g, color_.b, color_.a, - physics_body_, GetFixturesCount(), physics_body_->GetType(), physics_body_->GetPosition().x, + (void*)this, (void*)entity_, entity_->name_.c_str(), name_.c_str(), color_.r, color_.g, color_.b, color_.a, + (void*)physics_body_, GetFixturesCount(), physics_body_->GetType(), physics_body_->GetPosition().x, physics_body_->GetPosition().y, physics_body_->GetAngle(), physics_body_->GetAngularDamping(), physics_body_->GetLinearDamping()); } diff --git a/flatland_server/src/dummy_world_plugin.cpp b/flatland_server/src/dummy_world_plugin.cpp index 5a729fa2..94cf9fde 100644 --- a/flatland_server/src/dummy_world_plugin.cpp +++ b/flatland_server/src/dummy_world_plugin.cpp @@ -73,6 +73,10 @@ void DummyWorldPlugin::OnInitialize(const YAML::Node & plugin_reader, YamlReader "\"DummyWorldPluginType\", the type is " + type_); } + + // Avoid -Wunused-parameter warnings - remove if parameter is used! + (void)plugin_reader; + (void)world_config; } } // namespace flatland_plugins diff --git a/flatland_server/src/interactive_marker_manager.cpp b/flatland_server/src/interactive_marker_manager.cpp index d1daf87e..908e2802 100644 --- a/flatland_server/src/interactive_marker_manager.cpp +++ b/flatland_server/src/interactive_marker_manager.cpp @@ -193,12 +193,18 @@ void InteractiveMarkerManager::processMouseDownFeedback( const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr & feedback) { manipulating_model_ = true; + + // Avoid -Wunused-parameter warnings - remove if parameter is used! + (void)feedback; } void InteractiveMarkerManager::processPoseUpdateFeedback( const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr & feedback) { pose_update_stamp_ = rclcpp::Clock(RCL_SYSTEM_TIME).now(); + + // Avoid -Wunused-parameter warnings - remove if parameter is used! + (void)feedback; } void InteractiveMarkerManager::update() diff --git a/flatland_server/src/joint.cpp b/flatland_server/src/joint.cpp index 5a7996a3..4b276534 100644 --- a/flatland_server/src/joint.cpp +++ b/flatland_server/src/joint.cpp @@ -202,8 +202,8 @@ void Joint::DebugOutput() const "Joint %p: model(%p, %s) name(%s) color(%f,%f,%f,%f) " "physics_joint(%p) body_A(%p, %s) anchor_A_world(%f, %f) " "body_B(%p, %s) anchor_B_world(%f, %f)", - this, model_, model_->name_.c_str(), name_.c_str(), color_.r, color_.g, color_.b, color_.a, - physics_joint_, body_A, body_A->name_.c_str(), j->GetAnchorA().x, j->GetAnchorA().y, body_B, + (void*)this, (void*)model_, model_->name_.c_str(), name_.c_str(), color_.r, color_.g, color_.b, color_.a, + (void*)physics_joint_, (void*)body_A, body_A->name_.c_str(), j->GetAnchorA().x, j->GetAnchorA().y, (void*)body_B, body_B->name_.c_str(), j->GetAnchorB().x, j->GetAnchorB().y); } diff --git a/flatland_server/src/layer.cpp b/flatland_server/src/layer.cpp index f31b82bc..8a53936b 100644 --- a/flatland_server/src/layer.cpp +++ b/flatland_server/src/layer.cpp @@ -105,6 +105,9 @@ Layer::Layer( const std::vector & names, const Color & color, const YAML::Node & properties) : Entity(node, physics_world, names[0]), names_(names), cfr_(cfr), viz_name_("layers/l_" + names[0]) { + // Avoid -Wunused-parameter warnings - remove if parameter is used! + (void)color; + (void)properties; } Layer::~Layer() { delete body_; } @@ -327,7 +330,7 @@ void Layer::DebugOutput() const rclcpp::get_logger("Layer"), "Layer %p: physics_world(%p) name(%s) names(%s) " "category_bits(0x%X)", - this, physics_world_, name_.c_str(), names.c_str(), category_bits); + (void*)this, (void*)physics_world_, name_.c_str(), names.c_str(), category_bits); if (body_ != nullptr) { body_->DebugOutput(); diff --git a/flatland_server/src/model.cpp b/flatland_server/src/model.cpp index 99b6528f..7223fec9 100644 --- a/flatland_server/src/model.cpp +++ b/flatland_server/src/model.cpp @@ -285,7 +285,7 @@ void Model::DebugOutput() const rclcpp::get_logger("Model"), "Model %p: physics_world(%p) name(%s) namespace(%s) " "num_bodies(%lu) num_joints(%lu)", - this, physics_world_, name_.c_str(), namespace_.c_str(), bodies_.size(), joints_.size()); + (void*)this, (void*)physics_world_, name_.c_str(), namespace_.c_str(), bodies_.size(), joints_.size()); for (const auto & body : bodies_) { body->DebugOutput(); diff --git a/flatland_server/src/service_manager.cpp b/flatland_server/src/service_manager.cpp index 6757acc2..7d7e2836 100644 --- a/flatland_server/src/service_manager.cpp +++ b/flatland_server/src/service_manager.cpp @@ -107,6 +107,9 @@ bool ServiceManager::ChangeRate( response->message = std::string(e.what()); } + // Avoid -Wunused-parameter warnings - remove if parameter is used! + (void)request_header; + return true; } @@ -135,6 +138,9 @@ bool ServiceManager::SpawnModel( rclcpp::get_logger("ServiceManager"), "Failed to load model! Exception: %s", e.what()); } + // Avoid -Wunused-parameter warnings - remove if parameter is used! + (void)request_header; + return true; } @@ -156,6 +162,9 @@ bool ServiceManager::DeleteModel( response->message = std::string(e.what()); } + // Avoid -Wunused-parameter warnings - remove if parameter is used! + (void)request_header; + return true; } @@ -179,6 +188,9 @@ bool ServiceManager::MoveModel( response->message = std::string(e.what()); } + // Avoid -Wunused-parameter warnings - remove if parameter is used! + (void)request_header; + return true; } @@ -188,6 +200,12 @@ bool ServiceManager::Pause( std::shared_ptr response) { world_->Pause(); + + // Avoid -Wunused-parameter warnings - remove if parameter is used! + (void)request_header; + (void)request; + (void)response; + return true; } @@ -197,6 +215,12 @@ bool ServiceManager::Resume( std::shared_ptr response) { world_->Resume(); + + // Avoid -Wunused-parameter warnings - remove if parameter is used! + (void)request_header; + (void)request; + (void)response; + return true; } @@ -206,6 +230,12 @@ bool ServiceManager::TogglePause( std::shared_ptr response) { world_->TogglePaused(); + + // Avoid -Wunused-parameter warnings - remove if parameter is used! + (void)request_header; + (void)request; + (void)response; + return true; } }; // namespace flatland_server diff --git a/flatland_server/test/plugin_manager_test.cpp b/flatland_server/test/plugin_manager_test.cpp index 08f9fb04..a2ce9d36 100644 --- a/flatland_server/test/plugin_manager_test.cpp +++ b/flatland_server/test/plugin_manager_test.cpp @@ -86,16 +86,27 @@ class TestModelPlugin : public ModelPlugin function_called["PostSolve"] = false; } - void OnInitialize(const YAML::Node & config) override { function_called["OnInitialize"] = true; } + void OnInitialize(const YAML::Node & config) override { + function_called["OnInitialize"] = true; + + // Avoid -Wunused-parameter warnings - remove if parameter is used! + (void)config; + } void BeforePhysicsStep(const Timekeeper & timekeeper) override { function_called["BeforePhysicsStep"] = true; + + // Avoid -Wunused-parameter warnings - remove if parameter is used! + (void)timekeeper; } void AfterPhysicsStep(const Timekeeper & timekeeper) override { function_called["AfterPhysicsStep"] = true; + + // Avoid -Wunused-parameter warnings - remove if parameter is used! + (void)timekeeper; } void BeginContact(b2Contact * contact) override @@ -114,12 +125,18 @@ class TestModelPlugin : public ModelPlugin { function_called["PreSolve"] = true; FilterContact(contact, entity, fixture_A, fixture_B); + + // Avoid -Wunused-parameter warnings - remove if parameter is used! + (void)oldManifold; } void PostSolve(b2Contact * contact, const b2ContactImpulse * impulse) override { function_called["PostSolve"] = true; FilterContact(contact, entity, fixture_A, fixture_B); + + // Avoid -Wunused-parameter warnings - remove if parameter is used! + (void)impulse; } };