From 5bf0da5b58930cba57a314d598c2cd8c66e930eb Mon Sep 17 00:00:00 2001 From: "mergify[bot]" <37929162+mergify[bot]@users.noreply.github.com> Date: Wed, 9 Oct 2024 17:28:52 +0100 Subject: [PATCH 01/47] [CM] Throw an exception when the components initially fail to be in the required state (backport #1729) (#1777) --- controller_manager/src/controller_manager.cpp | 18 ++++++++++++++++-- 1 file changed, 16 insertions(+), 2 deletions(-) diff --git a/controller_manager/src/controller_manager.cpp b/controller_manager/src/controller_manager.cpp index 85aee476a8..ab89c8760c 100644 --- a/controller_manager/src/controller_manager.cpp +++ b/controller_manager/src/controller_manager.cpp @@ -395,7 +395,14 @@ void ControllerManager::init_resource_manager(const std::string & robot_descript RCLCPP_INFO( get_logger(), "Setting component '%s' to '%s' state.", component.c_str(), state.label().c_str()); - resource_manager_->set_component_state(component, state); + if ( + resource_manager_->set_component_state(component, state) == + hardware_interface::return_type::ERROR) + { + throw std::runtime_error( + "Failed to set the initial state of the component : " + component + " to " + + state.label()); + } components_to_activate.erase(component); } } @@ -459,7 +466,14 @@ void ControllerManager::init_resource_manager(const std::string & robot_descript { rclcpp_lifecycle::State active_state( State::PRIMARY_STATE_ACTIVE, hardware_interface::lifecycle_state_names::ACTIVE); - resource_manager_->set_component_state(component, active_state); + if ( + resource_manager_->set_component_state(component, active_state) == + hardware_interface::return_type::ERROR) + { + throw std::runtime_error( + "Failed to set the initial state of the component : " + component + " to " + + active_state.label()); + } } } } From b6ab06eef024c90128acc9514a4115a8845f27dc Mon Sep 17 00:00:00 2001 From: "mergify[bot]" <37929162+mergify[bot]@users.noreply.github.com> Date: Thu, 10 Oct 2024 08:54:15 +0100 Subject: [PATCH 02/47] Add `PoseSensor` semantic component (#1775) (#1785) --- controller_interface/CMakeLists.txt | 8 ++ .../semantic_components/pose_sensor.hpp | 110 ++++++++++++++++++ controller_interface/package.xml | 2 + .../test/test_pose_sensor.cpp | 98 ++++++++++++++++ .../test/test_pose_sensor.hpp | 59 ++++++++++ doc/release_notes.rst | 5 + 6 files changed, 282 insertions(+) create mode 100644 controller_interface/include/semantic_components/pose_sensor.hpp create mode 100644 controller_interface/test/test_pose_sensor.cpp create mode 100644 controller_interface/test/test_pose_sensor.hpp diff --git a/controller_interface/CMakeLists.txt b/controller_interface/CMakeLists.txt index 4f28622bd6..7486ee3414 100644 --- a/controller_interface/CMakeLists.txt +++ b/controller_interface/CMakeLists.txt @@ -44,6 +44,7 @@ if(BUILD_TESTING) find_package(hardware_interface REQUIRED) find_package(sensor_msgs REQUIRED) + find_package(geometry_msgs REQUIRED) ament_add_gmock(test_controller_interface test/test_controller_interface.cpp) target_link_libraries(test_controller_interface ${PROJECT_NAME}) @@ -88,6 +89,13 @@ if(BUILD_TESTING) hardware_interface sensor_msgs ) + + ament_add_gmock(test_pose_sensor test/test_pose_sensor.cpp) + target_include_directories(test_pose_sensor PRIVATE include) + ament_target_dependencies(test_pose_sensor + hardware_interface + geometry_msgs + ) endif() ament_export_dependencies( diff --git a/controller_interface/include/semantic_components/pose_sensor.hpp b/controller_interface/include/semantic_components/pose_sensor.hpp new file mode 100644 index 0000000000..60dbecd718 --- /dev/null +++ b/controller_interface/include/semantic_components/pose_sensor.hpp @@ -0,0 +1,110 @@ +// Copyright 2024 FZI Forschungszentrum Informatik +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +#ifndef SEMANTIC_COMPONENTS__POSE_SENSOR_HPP_ +#define SEMANTIC_COMPONENTS__POSE_SENSOR_HPP_ + +#include +#include +#include + +#include "geometry_msgs/msg/pose.hpp" +#include "semantic_components/semantic_component_interface.hpp" + +namespace semantic_components +{ + +class PoseSensor : public SemanticComponentInterface +{ +public: + /// Constructor for a standard pose sensor with interface names set based on sensor name. + explicit PoseSensor(const std::string & name) : SemanticComponentInterface{name, 7} + { + // Use standard interface names + interface_names_.emplace_back(name_ + '/' + "position.x"); + interface_names_.emplace_back(name_ + '/' + "position.y"); + interface_names_.emplace_back(name_ + '/' + "position.z"); + interface_names_.emplace_back(name_ + '/' + "orientation.x"); + interface_names_.emplace_back(name_ + '/' + "orientation.y"); + interface_names_.emplace_back(name_ + '/' + "orientation.z"); + interface_names_.emplace_back(name_ + '/' + "orientation.w"); + + // Set all sensor values to default value NaN + std::fill(position_.begin(), position_.end(), std::numeric_limits::quiet_NaN()); + std::fill(orientation_.begin(), orientation_.end(), std::numeric_limits::quiet_NaN()); + } + + virtual ~PoseSensor() = default; + + /// Update and return position. + /*! + * Update and return current pose position from state interfaces. + * + * \return Array of position coordinates. + */ + std::array get_position() + { + for (size_t i = 0; i < 3; ++i) + { + position_[i] = state_interfaces_[i].get().get_value(); + } + + return position_; + } + + /// Update and return orientation + /*! + * Update and return current pose orientation from state interfaces. + * + * \return Array of orientation coordinates in xyzw convention. + */ + std::array get_orientation() + { + for (size_t i = 3; i < 7; ++i) + { + orientation_[i - 3] = state_interfaces_[i].get().get_value(); + } + + return orientation_; + } + + /// Fill pose message with current values. + /** + * Fill a pose message with current position and orientation from the state interfaces. + */ + bool get_values_as_message(geometry_msgs::msg::Pose & message) + { + // Update state from state interfaces + get_position(); + get_orientation(); + + // Set message values from current state + message.position.x = position_[0]; + message.position.y = position_[1]; + message.position.z = position_[2]; + message.orientation.x = orientation_[0]; + message.orientation.y = orientation_[1]; + message.orientation.z = orientation_[2]; + message.orientation.w = orientation_[3]; + + return true; + } + +protected: + std::array position_; + std::array orientation_; +}; + +} // namespace semantic_components + +#endif // SEMANTIC_COMPONENTS__POSE_SENSOR_HPP_ diff --git a/controller_interface/package.xml b/controller_interface/package.xml index ca23197bf5..3aca05b65f 100644 --- a/controller_interface/package.xml +++ b/controller_interface/package.xml @@ -22,6 +22,8 @@ rclcpp_lifecycle ament_cmake_gmock + geometry_msgs + sensor_msgs ament_cmake diff --git a/controller_interface/test/test_pose_sensor.cpp b/controller_interface/test/test_pose_sensor.cpp new file mode 100644 index 0000000000..1ceb7c32a6 --- /dev/null +++ b/controller_interface/test/test_pose_sensor.cpp @@ -0,0 +1,98 @@ +// Copyright (c) 2024, FZI Forschungszentrum Informatik +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +#include "test_pose_sensor.hpp" + +void PoseSensorTest::SetUp() +{ + full_interface_names_.reserve(size_); + for (const auto & interface_name : interface_names_) + { + full_interface_names_.emplace_back(sensor_name_ + '/' + interface_name); + } +} + +void PoseSensorTest::TearDown() { pose_sensor_.reset(nullptr); } + +TEST_F(PoseSensorTest, validate_all) +{ + // Create sensor + pose_sensor_ = std::make_unique(sensor_name_); + EXPECT_EQ(pose_sensor_->name_, sensor_name_); + + // Validate reserved space for interface_names_ and state_interfaces_ + // As state_interfaces_ are not defined yet, use capacity() + ASSERT_EQ(pose_sensor_->interface_names_.size(), size_); + ASSERT_EQ(pose_sensor_->state_interfaces_.capacity(), size_); + + // Validate default interface_names_ + EXPECT_TRUE(std::equal( + pose_sensor_->interface_names_.cbegin(), pose_sensor_->interface_names_.cend(), + full_interface_names_.cbegin(), full_interface_names_.cend())); + + // Get interface names + std::vector interface_names = pose_sensor_->get_state_interface_names(); + + // Assign values to position + hardware_interface::StateInterface position_x{ + sensor_name_, interface_names_[0], &position_values_[0]}; + hardware_interface::StateInterface position_y{ + sensor_name_, interface_names_[1], &position_values_[1]}; + hardware_interface::StateInterface position_z{ + sensor_name_, interface_names_[2], &position_values_[2]}; + + // Assign values to orientation + hardware_interface::StateInterface orientation_x{ + sensor_name_, interface_names_[3], &orientation_values_[0]}; + hardware_interface::StateInterface orientation_y{ + sensor_name_, interface_names_[4], &orientation_values_[1]}; + hardware_interface::StateInterface orientation_z{ + sensor_name_, interface_names_[5], &orientation_values_[2]}; + hardware_interface::StateInterface orientation_w{ + sensor_name_, interface_names_[6], &orientation_values_[3]}; + + // Create state interface vector in jumbled order + std::vector temp_state_interfaces; + temp_state_interfaces.reserve(7); + + temp_state_interfaces.emplace_back(position_z); + temp_state_interfaces.emplace_back(orientation_y); + temp_state_interfaces.emplace_back(orientation_x); + temp_state_interfaces.emplace_back(position_x); + temp_state_interfaces.emplace_back(orientation_w); + temp_state_interfaces.emplace_back(position_y); + temp_state_interfaces.emplace_back(orientation_z); + + // Assign interfaces + pose_sensor_->assign_loaned_state_interfaces(temp_state_interfaces); + EXPECT_EQ(pose_sensor_->state_interfaces_.size(), size_); + + // Validate correct position and orientation + EXPECT_EQ(pose_sensor_->get_position(), position_values_); + EXPECT_EQ(pose_sensor_->get_orientation(), orientation_values_); + + // Validate generated message + geometry_msgs::msg::Pose temp_message; + ASSERT_TRUE(pose_sensor_->get_values_as_message(temp_message)); + EXPECT_EQ(temp_message.position.x, position_values_[0]); + EXPECT_EQ(temp_message.position.y, position_values_[1]); + EXPECT_EQ(temp_message.position.z, position_values_[2]); + EXPECT_EQ(temp_message.orientation.x, orientation_values_[0]); + EXPECT_EQ(temp_message.orientation.y, orientation_values_[1]); + EXPECT_EQ(temp_message.orientation.z, orientation_values_[2]); + EXPECT_EQ(temp_message.orientation.w, orientation_values_[3]); + + // Release state interfaces + pose_sensor_->release_interfaces(); + ASSERT_EQ(pose_sensor_->state_interfaces_.size(), 0); +} diff --git a/controller_interface/test/test_pose_sensor.hpp b/controller_interface/test/test_pose_sensor.hpp new file mode 100644 index 0000000000..c2344caaa2 --- /dev/null +++ b/controller_interface/test/test_pose_sensor.hpp @@ -0,0 +1,59 @@ +// Copyright (c) 2024, FZI Forschungszentrum Informatik +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef TEST_POSE_SENSOR_HPP_ +#define TEST_POSE_SENSOR_HPP_ + +#include + +#include +#include +#include +#include + +#include "semantic_components/pose_sensor.hpp" + +class TestablePoseSensor : public semantic_components::PoseSensor +{ + FRIEND_TEST(PoseSensorTest, validate_all); + +public: + // Use default interface names + explicit TestablePoseSensor(const std::string & name) : PoseSensor{name} {} + + virtual ~TestablePoseSensor() = default; +}; + +class PoseSensorTest : public ::testing::Test +{ +public: + void SetUp(); + void TearDown(); + +protected: + const size_t size_ = 7; + const std::string sensor_name_ = "test_pose_sensor"; + + std::vector full_interface_names_; + const std::vector interface_names_ = { + "position.x", "position.y", "position.z", "orientation.x", + "orientation.y", "orientation.z", "orientation.w"}; + + std::array position_values_ = {{1.1, 2.2, 3.3}}; + std::array orientation_values_ = {{4.4, 5.5, 6.6, 7.7}}; + + std::unique_ptr pose_sensor_; +}; + +#endif // TEST_POSE_SENSOR_HPP_ diff --git a/doc/release_notes.rst b/doc/release_notes.rst index a1c76f6caf..a945ff668e 100644 --- a/doc/release_notes.rst +++ b/doc/release_notes.rst @@ -7,3 +7,8 @@ This list summarizes the changes between Galactic (previous) and Humble (current .. note:: This list was created in July 2024, earlier changes may not be included. + +controller_interface +******************** + +* The new ``PoseSensor`` semantic component provides a standard interface for hardware providing cartesian poses (`#1775 `_) From f3e7db62503a02843d223b5437097486758774a5 Mon Sep 17 00:00:00 2001 From: "mergify[bot]" <37929162+mergify[bot]@users.noreply.github.com> Date: Thu, 10 Oct 2024 09:01:20 +0100 Subject: [PATCH 03/47] [CM] Handle other exceptions while loading the controller plugin (#1731) (#1733) --- controller_manager/src/controller_manager.cpp | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/controller_manager/src/controller_manager.cpp b/controller_manager/src/controller_manager.cpp index ab89c8760c..6d8bae1f28 100644 --- a/controller_manager/src/controller_manager.cpp +++ b/controller_manager/src/controller_manager.cpp @@ -570,13 +570,21 @@ controller_interface::ControllerInterfaceBaseSharedPtr ControllerManager::load_c controller = chainable_loader_->createSharedInstance(controller_type); } } - catch (const pluginlib::CreateClassException & e) + catch (const std::exception & e) { RCLCPP_ERROR( - get_logger(), "Error happened during creation of controller '%s' with type '%s':\n%s", + get_logger(), "Caught exception while loading the controller '%s' of plugin type '%s':\n%s", controller_name.c_str(), controller_type.c_str(), e.what()); return nullptr; } + catch (...) + { + RCLCPP_ERROR( + get_logger(), + "Caught unknown exception while loading the controller '%s' of plugin type '%s'", + controller_name.c_str(), controller_type.c_str()); + throw; + } ControllerSpec controller_spec; controller_spec.c = controller; From 4ed2ee01505e340cb268211fd9a61fc50dd11946 Mon Sep 17 00:00:00 2001 From: "mergify[bot]" <37929162+mergify[bot]@users.noreply.github.com> Date: Fri, 11 Oct 2024 09:48:38 +0100 Subject: [PATCH 04/47] [rqt_controller_manager] Add hardware components (#1455) (#1586) --- .../doc/images/rqt_controller_manager.png | Bin 0 -> 49114 bytes controller_manager/doc/userdoc.rst | 16 + rqt_controller_manager/package.xml | 5 +- .../resource/controller_manager.ui | 36 ++- .../{controller_info.ui => popup_info.ui} | 3 - .../controller_manager.py | 305 +++++++++++++++--- 6 files changed, 316 insertions(+), 49 deletions(-) create mode 100644 controller_manager/doc/images/rqt_controller_manager.png rename rqt_controller_manager/resource/{controller_info.ui => popup_info.ui} (96%) diff --git a/controller_manager/doc/images/rqt_controller_manager.png b/controller_manager/doc/images/rqt_controller_manager.png new file mode 100644 index 0000000000000000000000000000000000000000..01c4f55bdf1021623377c893c95e6240d67b24ed GIT binary patch literal 49114 zcmc$_byQSu_%BLJDGE}Of`oKP4`qN#i_+cQ-6J3!N;iUnN_Te*ox;#Hba%&n`L1(* zN4@vYyVh|nm$Q)Bd%yKOpV~q4vXXbPA7LXQA>DoR`sF($Bve-l{vQ2St(PZeTs2G)WTJV(B{XH&dE&H4e zf8>`$x8>hI6?3lDN{o6sqZr~;BYT8^W-&>u%0i~eFp(NJ`-32d} z^~3rneON>Q9UTKLE9+JR1@t)f->W&GgqD2Cb76k`_;Iew-a;=n5#xRP-GQ$kMkOS# zzG9yk)0!te-^@_WGUzmqNaOz+DHu7i$dBaf^MRVLD;ukP+I(9+Q6m~Ezrew&c^ zdtZpnp^*fuwuOzsS*? z4R#@)Ky!mJwM%2SG-TO1a^)*I>%R+yObmUeqyw)oL17D(65k6vj7S!W#t)y(t72&o zR71KG#eLAR-}8XEqdPgS{GWB1Q%H9ne5s*LgFL94nx?ANjE&^p&X8gL`H6?i52P&e zBlEx%SaB`u`^Xg;$&G*Z>*-^T+TWxO6)61P_`Z$mZ&Ss`e>|&oPfr)EF)$-TcTHFr zYQG)dYX?iF3H_m^(EnE3Kq+0W z=w$;c1YSG-tAas*ToH9DV`XPEF+o_?k{z64>J%{-X@&PcJ`fmUFGAwef3p@NpNsJ0 zx8&E5hXvmpeAqBm?L)|i6^o0dRauDjExkfp;{MVt^WGC{@jdj5!aWUb$Yal==2|~h zs|~BdYUkK2Uwf<+Ih*SZPkocU2zk`kLWHT-pF1zN1ht$ zBX{Ylkw19~5;w4)Qbbwhtjt1Y>pSH3DwSS@YjvUe`Z~oeI z<_O!-F-ZS#nL+(1_CA+&mhh8EQS@f!uZUgsf$R^czkkT1_|xLs8XOovoDOPKKC6+- z6jY=09oF7IVty!Yu#ZJPQA3bK?D3I!_UvweMNx+v$?-S@x8zz@>ze5t?*`>!$Qzbo zPNsx*9)oz`WyW`XuJ=sBs}dz>o^BxbhGXh?HpO~Oc=MWY&R+Klg2Spy zo4?7rGca-Wszb9f!;3DOjVNLaZ|8YUGL_FQbzqv=i`;o(D6Z(GV&Bp+$O{Sf?>#>}I=9yt9T^%!ra=t<~h$?>e4 zgBLQ~DPPJlH`*twMVRVq!{Tsw7j)k0M(2&Al@&e|GL7C5wWp%4cEC!ujKGuJ3r8K; z@^wA^s4q*K=WPuymBY`OoT7&lmzZ2Qf@Uc&Ci?9T{@ih=BfhU-uRCrY){pb@T_iE)tEI=# zOX~ZogqH3OFS$4PT=&;#`4d%;iheTW&82fBPG4haRaFaSeEz5?8NTpd8qzgt;`h#! z=fTdSMFD(Uhkh;c3Y4hmI@ncZi}wAafco$vIQ*6Px5s;noKM=LUnL{ZzO>}p?G$!x zY4=9EpBvCDFr@{|(2}LgUUJ~xmH0eF&nll?i28;hV&OEQnNg{V&TZxfW#|~U zF&_1~##DaHh$|P8@X+=7 zyr5RWXn zSejs!ceAE@nMlq4nqI5#jmqA=)$x3i=Dhx<;v08N{j9BW5nE}Pt==A`#hkk5vdt5o zM~)#dwZ|Hd!pZrAY3Rr@`(y5M8g9OQsX2fr{3`(QyXl1ziv|kks}R~5?9<~#c>f29 z8!O-Ql(nT7`5!<XYN@AI7%*=#Z%@|e2tq?-7 z2!&VjzJuS_dT6uRzUc0jAqkhQv=}oUQ{Cs98h~M!l1p-&_#>}+oe{2HTtZwf!{1Ja zzB#$q$fK+sCNAd{;JY$&`j&x6tC-trUHcAtUhPVq2P@mo&|OXTtxuDplPJ;kxbTyF zvzQt@QIQ#9O(Ex&bY&tnRu_NylSFY7f{iaR`grw}x+7JSJT6=P+%|r3&Hh^(>YAMz zUn;6y`HdR7kM~G1*{4b2NBID&OG$FN@H`ot`4f)2$UOM;T5!ehwBTc|UQsE(UR~pMx6`?clQ-lKvlS2)*C8B$7sGdS$s)&GF zG{v_?3CBTYFe8vJO?xK|Yh|s&H;vieg0f!p<59}md}iJ&uo5DKyZG+QiVrBt(Vom@ z`=EAqJ`K#DMk>q9yEum}>#pZgWaVh4(+`B^PLdqqsJT*IQD}SDpc{`lavnX*m0*0C zW?VK_G)0TUiHP$Y?SHLv;apO58GbOxR(|i%`=Cbltg|+{@7pkK?;T0CZl*wXh2PTH zO;?w4H-l$EkH{N3RR`>%$B_br$(vGClobe=Xo7{tt z4BOFwq0c@9>P8C}0`R%ZZQ_jCU4zzg#=vhQvvWyp=!3tj)9x!3VlJFA)AAH}=4T9U z?!~f#4C}v&+wcD}=WT4HQmO=Cpf~~l=91L3BW~)n=CEUE zs{8kQ-whnl?PiBgX0i7@$V_ptUNbB?#ncs z07tJLEbNkdR~Db1zPTx_xYk#woVIi^m~#yjs(Pf|z)hMX3zyh&&zFcIDM^AYZm)4i zaFnBPUXi^|iL!M{sC<}QZcKcfB`D8UjGf5G9u|}&T)J$yS6f5&nE8gXSmjutTw_<; zqXlulTiiK3ir;JhA(32ac;0lrB!amb#T2%8pj=XT@Y0xjhKGfP$kxAEzVgHMm4@LW zRq2j&1iIN*v|`Cd_&0h|nNMGY%W$-wx<}F4Fw$Kn+q&ZJLc*F#V5?OT-9jcyMeJgT zJ(p7K{g2LlF(qjG{$gEydGs7VHFMD?_`+J!Lgc8qxI8yPY4@JUayBxWgzfz@o4%TH zL(%;_3YU8u470N3)#w_%JN9J={ccEk6JZLI&RMSJXv#k0hNKZ%pM^@8HTS?P>%C7R~eDOdjT`z}NGusYDCl#^DHj1U7evlvs1Zvu_sh!B4yM z+l5*4u*{G9+83)}bAbZBXkLdcIGKe<);v3&`Cm9rI%O+&-!xn+B$p^~G;sGnmBx7z z8HOV8H1L4X2IGsrwsS*TFbb8~w)ALkDT<|gGB-v)WhSxxJR$!c?8KRKq1Ys0U+Y`OzJZ8Vl-e;R3Gn+Vi`Dly9Ghju3K96x$r@yjJxURZf-29(^^q z_OsK(iJz1++gP`Cj&Cn6&g!12P(w?$=uykCW>-2QQ#-wPTGEytLWCaM;4_2g5fPDn z{30snSNd?2_SfEymoM9h%AW(ScC+st?>zJiiFuycHAfxeB5Ug;b90wsteO@*9K&{X zcNJDCI&W6XG22q?TC&^e?73%gvTx!&izZFw)MJMJG?2!hU~k$}n8U3}lr@6%H=Rw$ zaH03KAi1o$&pXyn`cro(iV!c!f3+D7_^lM_%)0I-dtIx0LuLjawH&o7SN?t>Vp{WD z=Sw-xu-27msXM~ySwukuGnFf`a`kW4tz8H5jT5)}n;!qRhZ2uBB(Pyl^taOKLRpErQ5ML_`+#fke9P%RUYTi^?z;vvm`Pre%W^@pG@?IdKSx%W-Qs`8&WmV zo9Crhxe#U-q4SGLBa3vL>Y}h zJdF_barV{-LB&#Fv=Ck~?C+ypQ(qmrr!yKNH$RN7Zu6{+I+!q|xszZtZoaCeXo#u- z!Qtg;#ZO6jL#wnSqT9Qx{m?(}jfxYwOxdzFB#2Ibr}YZq)u`>>PhG6@q;FF#oU~vz z%w1H){#Y_gG*R_u(#VHi<8f0VjwSy%PR}#8Bg z2(O`fTuZHaqH{P4ZjoUZ?d2}p0ps15%IzQY+Y$K(*gBJ~NgSssWnK_9+8vYC*C=$6 zHKNMreYn3@#Liw*m!h=1O_hkqNZ5dKAF1HZlu>@%wpOe5a8);-JgYBPc9zk8t_HX; znjH1I$JE|Tib>42D#p!2W0{Bhu(7W$2)qb9eN3$sJE^{^kv_L)FS8ZW^j=1xkqdfY z>)O&O(2SlVC2Iw(&03yXBd78a3jVHK<9gqREH%gXC(oSv z+!&8WORkzPyO|p-W7M~DgM{!;uEO#pb22P~h61HUg7c)7^(XG^Eab3W%fv>_|2#JP z5_dw2JiRh_cupksQr#R=sKrHX4aZOwijB$^x5mVyrY@80?A5s^Y?l zZB9+r?E4A%e*_>MbdsK}vX9kuk4aqdYk8X+A3f#!SI^mfAts(m^?KsvKi{=_ARig0 z-WR?8^l!zn5f2&N)r;Dc;GYXsy%H1GvJz1ImHpQvQzMI_JzPA4ev|n}by*|=*Qr{P z{+arhb_8UW`+ieQ)V#zQu*g0@EMhIfWYB89+%EQKF@Q+xaOC3mI33}{PFy#D7#+xNi?2=zso{W}Bf$PElydohzc z4L9Mmqqxas=5UETwX*w^`KN<%38PYfU49LHG+#4>fI)U{tVrK$uoVW&G#SjG$FP-C zKOt{BtlB7C+?gILL=>uO=Df2l&DExyo*WS$v3oV`+)3bVEYKnK`n8yf3W=Vc9&T%~ zVYhsiG->UA7jxy|kknv>^(+MWoA2MkaIvHh@=OA^v3#b)-3GF-p`oEd%Sql`?S`3W z{G8tf$WK=%mrfmy-{My0l5Ud^+zT_0hZaMte_R@!xqSMJ}J?Y}D6(_x5eDb`2NC z&v)Okc`YXl%8h;a7JvR^RQq;6tJY39Hbf9FzX6kee9C{9Zr^r;%khg27&8Jdwyb#^Nz&9a&M9I zj+XuYPVIs0`vNTr=ULB+Gj-5s{+Juge54u^uGn3^Mt#e%v4^CjYnwBjM72Y0h~34) zzRHuOHGYrHXOxr^55ml2TGqJVoI0)%c|i0@>$NK%^iPl9#S2R@RJ*d;9Av4y6Bkxx zY&ti!6sK*K_yUKRE!1q}SHfI4l#13GLqaC;S?BJ3qn>!(YWrAb<$FBlqpcs5HT_?O z5E)k1H85M%Z1L6}Pncg@ z{bAO14^L_@S&4F|KB;|pn_(ICYs_iOay2IN1iZA%(Q%Zm`24NL zJ<;m6Qv%JYuJ9{_MSEGyXKNn?w-UBaSl%hpYtfn-%ZW)yr>h}|_^w`I1x}BDP*^OB zs@|iXYNsu;M?=MlT!f2s3=H~+_ON(v<8X09b4ms+U1l{f@ZR{^(06)z8CYm(9{X>m zTo7T5+Vv2Af<8iJ4XCoV=g6kh`tPR%Pey+#-Z|QU^ND9tNJ}U44<<{;j+9%fmzs@q zC7WciH(cT?X3O%hx`vVQIXM*>P-={ReQ`&_rU~6>vSP*!M<$7v$J4W*;o6N{(4m9n zB&Pm+ojK~x#l`XZ2o88?$L)omluq<1i!>R3`3k{Vr>to>%npYVy+rSE zoZn<&_xjp!cCX;1_gJBBRv(0j?$4r#rtX6{*sKyAi$9!k-$`IgOnns0A7V5txU`4J z2+LCA9Q-_1e?oFhF6fWKsbEAg{53QC0U=?~b9DVeix!b*IqJw#@KlO&!cBy2Z`xj; zVVvft07|zGX+70)3suPZYG&nXMu>EXp^{?OM+h&OY!dHX2D#Lib#6z}NbO1x4D5P* z^-F$TsWcJKzVT>=@U&YPf8Yo@$H3{n&y`HoEuH)owE5$l{@_nrtMAXxwA>u^+6A4CE}|KFPMBkl-t>TdY3gerb6)2 za<-m=fL^-MzF*il!%c`n)N88t3Y_ZD!4UR(lPQm_ZXK8X#m-Z30K)E^ILolt?tUyX zhO3W8IcAllR0^x>-kc)va47_zP1m2l__N-OKb9}l5hp;ax)v$#Ued>ZG{O=>IEtI7 zpzvUH=ZY~$VSO{_Rb6nUyBOI4+4W5pTUoVLdwM$I;+BX>8}GdI1lRLBz&)oU?c+@>0BE|3Z_IofT(%M^p6(5tP?$(NhhH9so2M1i8Ra0>iAw;h<#JtItp& zxajGeZ#)pCbnzgEkbR&;zDcscFpoC|H!hN@#AljUTwTp*Q5N%d*7(as z_8Fw~attt@mdZ+ggdqcl0?X`?bfgZ6x1s9KmrWC}G_0M*9c&f>L8|PFD0k!>wWvS@jrcuQRc7Y)Cc^ z>*UUJRf;60Qf^FCSt2Rl5elDG+ALMu%gB?6!`yJTCNWcH3knm$%Pi*+mr^1i)8My? z>{Q=fOBB^dZKr_{owUwwh1%BM4X~eu9qmY$Epq-?u-_YF{ep}Qv)ZE`>se*CRmX6) zkg=1)rFV(M^&^oV51J+vz{wVUnhE2rEa&H>aq3MIe}pQhZOB2gz*&-%aivyam13Vv zwL#nwn@46<+0^r^Wjo1Y`rvmP4=sW91=njt$=$8R^Hgz$emvOBIIM#$1^1cdq!^{X z#1Y)?&kE*3ptC`Yz>|v-F3;7TS^rf<7FYVq^do;g|1n$7`r`_nBiYL$qX?{IY?TrV zt^xhH-uAM$h=ShH%349gI>HUd>5u3*()vW&m#kZI3)bdNLPrm&Yy%15hCGH$9VIxr zA$aQ3V_Oma_8O$HPEKkao%ZxzVa~Tp-uynq8z1 z(*vD$dF=EDrtG0!g^epSH}gikD1-g{9h;TDly>;+qNVon$3_&k;_=iK*a&ymi)=v( zKqVFU`MSnwtLF)0{ZJdRwnh8Sv?E;8NJ)m0>SRf!O6Oagw%2%Qiarjly0nnv`l2)E z%<&Q$Px6BpSWEf^=xA+lZEwr!IxbsWN>p=^J9~3YzD62P`c;j(PHHm#CPZGCh2KNi zuf3Lb6#KNBT$+b%a(*oZ>&+R4?ftH#+Fi6v*=zQjEt*LT^`GY2YK;}{i%_VrvpuXY z6r^;&aK~L8!kpr(A#fM6bMnA&a?%*8b~Nt+g`j8f^T^`PX)~|VFalB&`R&`2;k=06 zFXV{!PX4iA7^i#klpit*Du(RuuhI7C{OU}o+8ADcr8zLmkOFY_6pS~!R(HP9T9E6R zQyCW<>nkK4d37i%DwMy6q?S?!*Xtp?4i;Dv!4#9!w)4EraI12GTr`neOuODkNH|KK zigI5EOf;&WDfz0Zn_qcYPugh4euQjy&IWwivrVJ*NZ95uh=$(`!N>UR@Ry_~5 z?4%Rx9#v?JOhBj#oR;wET^3sgZ)WU}3Op~F^S7sveA%tPFrz>yl?Qww&Kk0N{jdl3 z6Q=0|#6#Zo;m=7Yc(hZ&*tj^175UPNR!ogDl0Vpw{1IZHZon*zBZbYL2}#ize_h;B z6>7A1oTy%5%<9)PrgW&+g^jPwjT9LTTBz0JlKK({vnAdvL5$oZPqdkGJn8<4$~4ya zG>B`(8o>{>N=N^pfRW%ZJzVsEtF`pce_(#}`B+Px&Ls6`MFO(A;8uj zsne<1F@JQu`x9mWx8(n~heyWSUxyb&z_r}(rU*Jd?~Y})-N>t;5fB)E@7eO{?&@eB z*)OHM;E6JGM5_C?`19uQD1`yLp zaD4joDakXF`+!;*u8&n%Yg^3LPbaL@dtPuDblg{L06*6SptsMFSt(Zxu+v^I%Zbva ze$ksvjcmSu=B`+ZdQO~@`5HWt&Sz8Ht*VxYjIT)i*tF}( z&Efg401l9*h>zbXgKLG*yb7KJV`!~*+~5F=t7LoN>x*vXZQt zXX@Nj4A;Z{*-)GJG2ceQ(w{Ohb=9)fpXw3xa2BEGg1IzuP2e(=W~M?F7vhX`JDm?u zNEbuaa2huZ3=M4!$-kNzRpN&39{#Im=PgIqG4T)fI| zX&11Jq#_60eG<pB%-r7RO$;eKL8u*=EeAfo{zdh5jS;ZGC*3djAo&~yiQ&#DiJ z{KyZ57BrVlSpnT@GgR*eAo7dfoGBk)V%w?zRg_LZ7iqG_EzGZn+Tps+9= zcBi(|;pnG|J(WVTmoIB`uV0MRYkAiR%`Zm#Yi{z+Bp3!mh_pwO^-xJRj_DO z4ulFDq~fAgg|mA6)yP1NDpsUc_pJq(Wxkue;Td9!-?Y=8SSx->e@UgmIMo%ydD=0K z)E*{gx!jY0iG#zf$pU0FFK$$N;|qxWGOk28`5KG)TqBfTMZdArXZPlM=cY$cHn*Aj zbBUFmQExCIv*3wtJs|TzrlgDfVtrGl6;nl0Pf;PV$IZ3@cON}#1osX7{rfiyRhrX3 zbv2R@$|34(rtfH)ys}a*;KnWT{42mbYn0xRnasIe|45C6Xy9g}qv!n|+9cx>UsiIs zZnf&aqjNVhV&XI22g5V}R2#c!vGP73;f7C9ddCs0X9)iNHGIrcAGLiH)?b%@He1lJ z{NzESz})*#`p>x*!vT$=^v8bGKaJu!XcUiIl?VU1Jqjym6ayJua{n|6Omq~Hn&tK| zGTVh#ETB{{`UQN?_@`GbT0rsX-cpN*P>$p%dR=T)_)uzz!4`jp z7>V_Vas55AeW+ME;)hT9;-Ge(%h{abj~9P0rCqLAqc4Q=CrTZ;d;JH_zaEMD4wj8< zlvuXU9bnbknMW!YXbIoaPX3$AgT1xvv_v>K=ctzX|IR&{4E5y4TRw=WJ?Lv0%~S8i zO@_)+d0%qYpDy5dfCs)2Fo#p~RAA)ZkcyN3y`oj`ZohmhXT)i_{S?QRm@`;OP?*t3 zjg9>T!lwlcT~#4D|G9h}oG8dCn!}R{oEEgcfRd$BaKuhGCc8Icv11j-xnx6Un4cCf2rCgPHmdVK^0Q3=Gq}VteO~#AAcfw>-yE+-!MQ#?Roo8P~(aSUjP=%8V;NL2* zacr9Mpm-i`PftRmQ-hG--&|iQ0OqV{6+tO{D?A&I_L%p?bDF^ODIW2d`8|H|i5lRE z0#A6Zs{V22ivq1W8!)wGFN9o$v}!a`@5rA0dh*9HgI=;Vl5&mbaAYc{8xI^VQ|!`{ z)X?>m$zw1#T%Us!@&@a0VteCv-Ih-(WoCrf4;g(xyGR8RsjSEV!mo6wFS_OAk*Qjgp94&%AbnaiN&PPtN_+PGXv5P zM_w=hHh9{mJ%XG?L25oPUHK-wxa8KgPffcO7S5@(76k_oPc zaF%q!N3eMwWXq;JPvW(d_OhI7tp4S`ks^ZoC03xF_``^bR431JJYS5y`jUEG;aw92M2jI zBh9))tv}DYfMz;KCoek}WzXw}s%{>Q+mestFLE;KZ)gC$Vi%y2c~ExSb5%>EePFF( z0n}-p$E2U`k{PKX;w2&|!`4S~5I}e~5=N!K@bc&<`T=T&K9Ey?y!#$J9K5mFdV<^D z6~}IUtZVZd$fU!?FbB}m5nC0ryyE!t36&}Cl(>}RdLsa{mE2V?yoDl#j{5*D@lDpm z>aXbY9!G9htxygJ!-&;~0ctc=TZkvIU{x({UF@`q#2wpwX7-!$ne_}r^XgVBH+Jp} zrx5zcYGZ+XRL-u>jz6f#D*ZuhrM}HzwLoKq50aogCvC z&`;K7?`I3Qz}h$JPu;?$aoQZyRcinMpbzWb@#eUGHT{J63sA{=od6-_x-m3Y2YQda zuy1P=gPfo*K}OXb^37!vcKvIM#}3n`Ygd z)WQp*V2I)qW|hKpEEUZgBOIz5Ss9r&?tX~A8iQ*xZpZ1YpC1~c>3yyW=SuxyVMN}fZ^!VbvT-+TX^J) z`7o1EyD!N)Ilt?M^Qg{I;5Lhhso#>6k+mMWA7&YDImraRq& zz&x6PylWD!+F7Ze8J^8Qn>4IkX=z}PNipabx^0i=7>of(enPWqr z_U-&l33IuZCH5<_!!%u&D4w;cxTVs6ZavozK2Qqpii4$dA<>#}K1PCqG3cF}?${b| zh?2GwFOzPTo-pD;c6}0b{KThfT@QK$odU@DtjGa4!z+&#zT9mwdXDdO;DBeQ;Y(I; ze81I)_36`2i;enJZ~Fy&*}i70*yQv@Ko+<)#RZT<+^-?XPL#>G{)o}Bu+L}QVumSO zKEFM+;rr9GHOm`6!}DEjacNMwWILLdfIAd^reRQ;)^Jg5&Uk?aD#!-?0HO%o6VHpP zAY0!?RQBp>$5@`Ic)(aJ4cQapko13j*q=2{2f%o3;Y+9pY7^$=$C)p%{KVu%zdMH6 zaw2DFw~RW$!@pZVA{;Tr{}W3+nx8Ff8ec#wEUIjb+R0`fTekpFeye{(#kID#Cl-0< zH(|~y=c+tlxd4)Q%Pj^6h(ED0PyXxkzVoVu$qR0uOF)aH2Rg?E$Ish1-ICXaMcCki z)uZg0C;61A;St^Wb;oKw3EZ&I1pPwe2s#J$ZXWiUKCn=HG9t=0r@QkmYv1F5NkL5F z?v79B9S&z>$V3ePC9l11tnj(8cAa%UooSxU{!$@ex7Y#E9=C0OEkX~S#@cFCCBK75 z849@C*@WiC3&zIu$f(X;PTaq7pV%>GA@V2TySExmiI}-ac=@Qrfu|+OVJxIC*>&(0 z@ptpigAY&h@amDM>KYTI1h8<`aRiPdBEDj_r})iLg}wd5I*JtAeu&w=vy*~XljZ^t%q*IJA#@WRP@m%CzzJJr|E; z=tgC2tpmOT%byJz+ymut2JC+=j`uPDxc1Qd zSO9Q7s0{|0g+C$ceO#zdUw#$v;B~ScBb$3`!6#eiNg>q4VJlsb~KH&{@1Gb;PKlCQ`(3+{i3&mmT ze`cQA9E_lNIjinTBg}bOO1N=p_8kGxWa39 zC#BXNeiqeYGyo`{cEvCU-1cP9V4eE%PeCKi^tw9#p;APHagRLE_YPj7BN?C7%kg5v zz5Q{ofZ z5K`oEw(r0#R84tD^yBd?;QB8BbdgR`FSjt=FM_)=F>q5(9B)dO*>zkt&?R(Ar$Gn2 zF=SIAK~27Qk~Wmi_Ll|$6i5an^A=z_ZB6)JUtJ`b5Bp&eL?$PP<`mRF0%{5`Jc?4- zO=n{?Z`p0Z)Sd0b>1yx{@9GRLFd#5sOl_YAZT#fovqKLI*bahU(XLPc$TI;1cDX)V z>Gj_R)ecaNsH#TKt0TAzz#N>G6VKlNdXMEiWqapVRq+6*EGzxC*KB#+Tsdz}*TB)N zlr?P80VFp5m=B~YeIVu-sb5^)YB5Hd4i3+N`()L%SSf^&aA^%Z>ms|Qw-4Dg#z;%Y zFD7nG@F)Zgx?F*C-E+L@))I0IbdH`^iJfKSp1inkvc6cR{7fk=0*3@jPQ5!QNtIwe z4(`-jW(559tQAaauD)ae0*(Hn8EM>owuVc)S}-}7czCdm&$PBD)6Pj7Y1vz@nZxiS zhCBCvVBhZc=k)h?so8mWcnt1DCE;8Hv?QX*1B5b;I`TQz2hQExNQ;f-UfV)cm_&sZC&1fMyJ zI(r$X-@VS7Olsgjigloa!~V03-h9OY7#=^A@)AqF_wvL6b%`I9myKPs`WZlEg+TGJ zcaF}pR8Uap^Tc_`h~yMigvxa?N`2jHm2g~T*Pmus*o}KoQDNI3;$4Ei3*@qA#Ck%v z;tyK(@p1l=feii4_L5nuH=)BKxT_UmB}iMy?0gaT#h3@|kAy=9i4wTQ_WEBsk0x4m ztbiaCFXCAZB%kyMcoYC<_I38NGhk6F5`X^3?NM$EjQp1y&NOU7rg$O_p&xd=;riPy z;wA9CJ`m`6m2I^}H( zEV=%g6c93L5E-6zPa2uKO+(r#JNNjgdt&Ac;MT z4AMYPZ3F3xh`VIG@q2e8gpWxCowq|zPhHZuYE`UeYR5O6$l)9SY*KOi?;6WqN54=SXJyW%wntL&M0U`wjI~6%vj^=0~+pxHSY9&G1(hji^=ld z(wU+QQRC6giLxBmq8UKLh*RCxpWZ6iR35uf(uh8#8lYVyktJFDEQ!kA^3?RUs}5Vw z_HH=GUFDv;COx%&JYD4;kW$lu_`(ZhyMz_nuw98GV0T2QlB|17f^y+XR^qjr(84k67PIi^l6_>4j=l^Jw#Voh8 zUh<3y$Xif?TNQndOHuZJ+Nv0efGjl|8(X>~wo4>TwdgPV2b}fSjiOMH#JH&Vnx>9^ z`2gE1HmCPbL~#2n|JQ5}lxs|M>pOOvW1JwYfPUv5dE;#qCJU(Pw}~c&GP4gLZ|6R# z`4`IjZ%_eZH!lLZ~Iv9PeR%+RqPav;xwU7+y&E#WhZvHSD$ zW;%zqGo`l`>`y!-2?Y=pcbAA=EA&Ocz4_hw7L_`CbnNJ0@xcXS^{sG9kzhZ|PLuaV zSRgECv)n_P>^$R&eF#ZqWBpssdNQX;y((h_nj&hA>GoI^>IS~@*Bu^Zz1L|;1KBMf zmL2uezOD{8@QpsnZQK^F=_#LrDNmFbRMT*MN2} zo(BhqS4Lp-9$BEnxM5tvr3i@Yh#AD?9N1Ji-UumEB{Ti^B5ErN(3A*Ly|2&i!=Ja^ z;Vg?3i_fkcCUSyw6MEH(|bhGV@QFx~&M1Yc^ zKU?oPS3ff(#a@So@wPXK4+c8E*>%oC52)MG`mLxe37V6%?yToY3f6fdujQl5<{N#i zO`4wSeMeA#Z{m}j!07>vR19mk{joJobrux$P6lw#p-j)uZlPX>GK%&8%0(!d5I;9{!Eu&lqGivRY<*zKn z^z>*dttEb1R|^LH?<@e=BJqH~sCoj_k`zlSyIHIcyN64{fds@h$-#_QgY};7x0s~Q zVl)3!rbHN5o&s)dmRwqD{^TOSf4#G;YNZ?(y+FUZoCXoh13vZp=D=?QYn=J|GmXi} zFG8cfP#A16 zXU1t-B9sLAnt$%B3S>!p{X`E}ipGAb6zOG&G~8U**d99cRkChO1K-KM<*P*4BN73- zZwdSzv!&*6HVyZ!vi3;Bq3(L|CWuQY%LO3KVr6C{@^x;G-X){|y@hUxw8 zaNvHjPVemtUV%VDydkjlUI9T!Iw9;4PcxqAWu%q*)#KZm*MNn_(}9pq^!VONucN%6 zL@p!Zm-#fnwx{;=dbZ)rOK!o*e3H9ReT++x6m(!7aU?*1Qf%Ow&IxltJGUx}7mM@S zP}`-?3Kxb|evs(;nQt2M9peK7u?}0GWb#kq6a>CRPNZcw^&nx_vkx+)@%dkGg%hj= zkbeAl+bhwi^MjD@cW+JC@V$*@M8+^5&XVEYQC$X3)Mu-U&}$NiOQGt~t*Lagk8%!B zV|>F}z^!NI5GVB36CVKj zub6g95+KjlN9uslS&kJpY3P%5>|s1=PrRg`1SpeV9mUH~{M^xM)Pu^5jIbEF4dtCsrG1FH%keM z%z-mN!9BC2bU8vlTdGS;%gfkI?marVqKnhebE*Q*(>tqlf2}Z8bhWU$N-(#vgQY|* zlpH`ij-9;pF^iq#LfoGH0i#_E^;QdAQ`l64tC6{>> zGh9YWQt_^;c{*$5_E)~wQvpX6^mDfPdgJx$yi{h_ZF;~tiG{CFE?_};TcLMtKaNTBn(V~=86Fuk;kkbzTi)FHV&8tthCFjZKS>RU1SU zt(gym zqDzwTT%2Vc7d|LNvJvjNq~9V!nU`WL#yBr}}` zc3VUyL@J$e1aS2IuWfMuy5P zw2z#6qw-v&Yt?%e&GD(+wc+;dhE55|7N3GxeUAkkZ=}avE3e@*-dhu8%Tv3C=&42o zC-#Wzgv02x*jrDuV-01q?f^)nNjtXX3q{1J4Zhce6 z4-o_<9D5h1poDNtUu+Q50z#Puf@{gr>{ZHdC!{YN;H!ydaO5MCiqSdiErN zK89n%(BHv$QaSge>1vTVUDR~ha3AanMc=v2fbTWN zqguv2$y1=dSkU|EinUwCZt`~QS>d{j#Y7;ob7P+!kc(kRNwbt^2!btxGOq-16)r@ghkz}3^`8=tJ#q88v-O~3 z&uP2!-VXt2n7P?>HBT?N{RhrwePYSdD zmnxv zVO*?!P6FZLbeVeVOC;p&(%(B_NG7q96^DQqo=0oeCx(-67K5(jd|)jWp8T zNZ)6Bj_1>F?!7a2=KgW-%y-U==lH(xzH9Hj_S(<$s};_qT(pLAC}$zPWBs&YNOmZn z3yj1SK#^#8^PtH3V z!%-FIe81aM$_} z2LIN@Euc9RwAk{!ee06haJTqDjO#T4VUj1Uous-mdfziMwR0Qd-<>5}`&^$=uX^?= z{Vno)!<62w+F}ji=7G_sFFa#WDl#9cLJBWTA1vX z?G_?8zva!&bSC*p{%6z_dw=PQ2N)ErH@cdiSI+-lXq6dzcs}M1M~Tyh=a!43nB$5v zFKOb>wfk4UN+FLjL_Gask-}Q2)MZ4#O>}=jd8_qa-?M+=ZkW#3JmW#MVtql54bp>t zI{?VILA-PRTbYS}_N|+*KpyF0^}#m$w^Isu+X-Tw3;C z9?Sbe6cYs|w{P8=#=S?H^v5>?tV$gpT5-+cvHTyt7Wl0v1n?ya_g1K&8vpH@Qea?F zH??|FJ^XK-6d?9!j!!~*-2NCVGiwD>p6=-N4O+Z zQ7;22#Xo4*zovft@ny+qk<@>#+TTNjpg8e>Fc5{@=NC+{)&m= zB9pMcwikQTyw@$+?jCSjsQd@X`MX9NrPDenm(rdFbQfwBLBiVicKz{fN|H%)X z>f+8fB%oJsxPlmArhPdKIO{p3GF>Wp5Zw_|Mw+qst}Oz=CNz#v7GQQs#pEL zhZb=ChPfTq;}^OY=wkpqnV`FUyJ1+r!*&_HW#!&UXWSRUhv?T`NO_%lAr;`Vog3V3CS-qlZO0pU)lL$u(`tR(+H`pndn7$f_$2!|f zN-bIekddHLWK6AEoLPFf2dFN$^ecGha1DdZ;SAvWc_^*jh`@hqqCHM34@@6fh8;wN*`Q}?vO+CeoI4{AEi0a5Ou zY>Vn+_Qn3JHvs)aC{(#Tb=^?_n?TL9Xe%~j1s;L{u{@2`uK z=FbtZa5(_`)2?q(wV(WKxj!pvABdyTPm?|*5>-cSUCtn3?%-j`w=|FcTOAxAMFH?B z5KJ87Jx3ZdMg6wQXw_l+t{Nb(o5*T@{_fJ1Hh%De!XXYw#Gdn8(H(d?_7^Y^r9*y# ztfbC6i+Y=tN1Lr1Lk4kIF;3<+b6W*s4ohz_;`7uC~6=Zz>uG6a&B_hLjbrIX{ds7Xpthcc zOSICC7UD_H7+|N(YgqSXqAiS(G5s2Ob4@J$yNWZNQ5?8$2?;6j#ivx^RWUZf%V8sJ2Gr83I$F zR-fl`%q;%?_9}~nM{9XQCii9c0Ly(u?N4G+@%2e@#tZ9&v7gW8ntLb}ZchQe>zDxy zEw}V+(>6eF5o>0==Igx3!5aPe3e%`cR@G#{g z<#(GFBf1*#hiW!=T4K`-z3v>MOi1V1DdC;e7{8&?J6YeT67|jLam&#H`F4YA6$R$#K_Sej}1{RvpOp zxw_Ihv+QF;Rb>#+SRR+123T(g|MAB0bddBqDE7m-3rs7EF8kN-n5VmH3`WjHf(yd< z#I!Fx#5(V|;(^`iRW{>bqqLciJlU`I3!>;%nNuVpv{g33ub?t3>k>&xH}l;dW1Ef9 zADCX9H=d+nr2nax^(;U+I+=U-6_GBI5gd`h*{h@)Eb!*lX0~=MQQt53$g+Lvwol2~ z<~49m!#dnSecHCowpf4c=({EA-{(<*B2|#AF<=9`8qPB(+1xj?8#qRfm{%OM`ZMlg zeS7DW8Zt77>a+WU#a-&WdlyUI5_+qSN4+BP?cKw@&}BlQ;&Y9b&R18dKNkZwM7qG`N%XlODmVASx=+_ zrno}e-8%d44@^5<+?{F7Gh0S)-fVnFV$krA*+CDlRcG=OHaAoFG}9-H@nweA>2EW= zeCEX`&)!m$=Q6vaPa{ZlmQ!0?m1&V49n~8C*5}U9x>uK}rl8rkLqEy(+htE^2%@CFz=^;+5)`qj=#@)cKXlt*&(I#g=b%<-`lyUKNvTrS_( z@}bQsY4jsy;rJ0A&R9NMZa23b>fisfp~OWIBn@g5pa*Y5kyx+DyI$d!be9f0={iuY z9!_bu)A=!)sGG40wrktA^F{o%`Qt^WBF`A*^d|Fx{pFTZk{7NY~=H1 zlB!<&_H8znrre1+_q)3An5=GYGm~~jfL<_>YHIk8r+%H*F{#g6R|s#TYoGrxm=)ld zU-bGcb~)JzEWNYZE!-*Dms39tbnaLbU$eS)uDs0B-EL2Juj_3f@qWso$pnn zQk*QEB~`v{7o(*lX{Ti?$s@gNSEn;M;b_-t1pa!*BcGKoD??c!we*mJnCDDK<)oEC z(>V7v@D=~va8nUKIFW+r9>6u+8#3l_J94n@aG2Zo<6h-7aQRR`QTccKkOQr@gHGqk zi7S|hqK6AGFq}Kromv$6G~|Y|;$97J&BiU+mpcnyV`-0n?@89^Hq3EVXmQ%?0OdirbP^#X5>cdk++9{t%y9;)FcV<(WDw$;BLJ>eW{R}E;)4muxx#evCC z(}UTl`&N&_i)J~EiXTi}6N6>2Ms;1q9NL+2U;^17#anup^XB1Kmh;N7&QbXBevgs! zJ1tla_Npb2%-j(yzS9|lN&Tn76wY5rrPF3ncoq3e0ZDILnM1fEP*HD zZk;$OOdwK4y^8s*@yp!ZXP-%9$^BZV9a`R&Ip|L(&ipLuEfqZq)V6NlsusVe!<2(- zH}y`SxHxZ^*B2`n!s+ z-i{wV#~2DvM_Ya99drlNXR;o1ONsG2e|)-t+a*k6dr6W&L6Y*uXMuQjyt?)hc9YX@ z)=JxAWqVXT8jl85n#>)S2TsA3rMFb7J@Ckn#M*sh$mt&Cj1Si=K3(4*W`0LmiuqBt ztxLp>7cDEooTnVlI0uv-mMx!fbM!KmOUlRo-nClg3uG^4M+7mksB-W*MCU|DTM3a` z=f^GH{;gH@9AOBcA7!)V4qW^%TM0!8*aBPW4a9c-?6z-B_PdgX1(z^iL&qMUODp$B;}5P($SnHb;Qx2#|GznH?zBdT{L%vazdHYGPD|{G zEFUWzlQ+5-)&xGj!a>2L@Hm5l`Q@fS0Fgg;(hcMM6f<==l_ zfCB5RSH=Iy$5P~Em;hPFn%o-y=PzjP5H!s(5=^r-U0wimz51ZVY8Hx@(i)JynpN)f zzp1!}_3zgz5_y8-Wo}1)3*^_AURA_WL|pd}*uR)6pBA{l;??rNW6Spm~Fy(K-d#`OuN)`Wk@1+o&gA2AT58_d<@un3f zqB@gq{(bHQ(lFOAVhk4s!W@p!sU|h z7ADNBcu0R2@VeVu-ELH|4j+n)dK!Y)5Y-weFeS;#A=7S{sqvZ)uhVue4#!9r-~M#a zbRG=AcCH${9p!p^7I2}a*+W#j^9-V&`EZYe`$!cqyA^O(ijxt|9mg*dWUNi$of@3m z^Kh1l9Xp4Z3^H=Sxu?IBU7iizYS&#*6b*u0(gI1(%fOItoR0+1nr+V>Jnth*h-cfm z^5bzBWKSY4{|s+=B2xFG4R-evm&IUrMKK2HwVT;5I_o*d&+T8>o^Ng~F}&I$ZP9z~ z0%uK`&4M=n@pcdr(NT50tE$9=FdcStG4|g81u=*G*nH4z3?UdAqNfQ|S_k9LHz4>d zfK|?=FB$2^ah2B`1cw#TH1BqokX;K+%BLefAYYx~GXf7Gyt2~=m)sl(z5<}wx{!Dg z$Rn$46>kK!VeVj_H#&}0?IgI}mS|;2Gi)Y2F}?|tnCXHAHlsb9scv_~T3X3-Z=r|k ziFvXPoEl+gP$aH^qp3)eW3+cBY3o)!;{?CJcmB&Aa5uKR@mS1(lhC{^^cnmq&)&H# zWfu6UgT{6jqJ1J4Stwmk@bU3K`BcLVHwc2Td17o3*RG;eOB^m00jbg5XKlOKn+NFy zgEgM#R?3#L=@?zqFkrF@c~)RJwgP40E0Hlrc?^EGWM37|0c9N=`-|ykZ2e->}51M@px4qpkz9~qA>=|-Ce7G^J>5XFw zh?;#T$B^#j0j_ipGmy;Zfnjk>AvgWn4kwI%8SJ)pmCjs>g5k7Eq{HR*7GSE2=Jpp2 zx?PH;Jogm*1ga)kMQRisvWqhZ9>I)vs3y6UF*uzQMvZ-FzW9yKF*z!{Axw7jCe2gI(W+$ayk4{UxJb+{@O}LA-8%nP_ z>-58=J2wJ^ru=hxW$2VMQEn^EZ9fuw(TpdEG2PwNb{wv}u8S-gU>`Pbr9%5ZnFnEuw zEcw&|0ZN2xVzC`*kc7)%s9NEWhduE)XqKM(X_u{WO)bhuAuoYR?0nzY)$!C-A5M|>%O>e6xH#x&KQDLGu#zEmiqPCJ>5@^RboPo z4K5Q{JWTGzP7y%Gqb@-q#`&;-p5DkxASgtuU=LowW_4?0-uV6Rks08sIxMYODeRFF z?-yA(G{JvMd;|Ow8`Fea2H>K{NDHS+US+CWO;e@1e9w`?YVaZdpQcXVg=bXYUpYXyS;o(oBkxL!~(P#jV5C1>s zTw3Ev1)U=g)$wd6WL+%HlBU)_gEhmhj+`w{AS8mZj0}Guic*s zSyDC|h`!$*)728+^1bP%e_P_6Ct0sO+;Nk}*A$xH=pc{yzf#YxPx_ME#qBS?lKVaZ ze%95+zxvEnhMrh=urWW_+BGj*xLxw0V3AgmZBWaXG;jwFPr*0++2f2yCIrT$DGG6} zLbvVDLajjk28FJHX_~J9EUoRtfhHy3@3^hR+*ZUm-0JUvBAR8H7Rz%9WeAn^x!rWr z`&IEPfBmX31TUkd#h{wC1o+M-JRcVjz zDU_U(hNc6|6 zcm;4wZ5$p`e^yj3Sa{PjazPcp#`5=o!qK44syd7B|NB5Nr{yTt_!9zFrXkEp2bt#} z328@CVC}L%o&nOMFW(A{bl{QHYRCES!Toa)tT2Pc0+i(CbwQ0#0#3zm;7l>A^+GF# zJUDw}lgvCH>>nWNHh{peVg~gx<(U?nyR)AxOojhAU}mfbWYaV?hp=*+!XuB}dRBsj zPb)m@>nEQ+i%%a0%y-*{iXE08FMZ38f$@?iPo(8+W5v9X|{!H3oeC%d~VR zR1pGioOg!|gh21G&RxVo`74 zY|eJZS;!?zA`0sb{$VLIWwpAE|c<|Rh@DAgU^WF(*5+f zWMR-$RPZ$lI&bf}PyH$;L!KC9h7eOCMMkJkj&_ZY{8+Wz&TMI{vb^$mcX;SEW3i-= zv@2PGL8p|tGn8*ZIY`i4z2DCzYxpy|VS;ojzTGtzeTmJZ9sBU!4-c`Ih6+-OAibw; z)jVzsLWD!CzZs=a`itJWWC!f{H&FRnprN7lLniyMQA*4*)J^AO7`cDqgz^$+T{&dD zQ>4LdpQ~z7S){FP*$0Pfj&_4IJ55va>|m48&CC-nH1-tBWJ;_`z0aogr(Q%}{9f`Y zwvr@l&mQFBwH7mU^$`6~OM~oe^T|*|!x8H^dzE8g4WgMD?3BY@xoqY&LEjPsrq(vs zAA3;!#0WvkfOX9M)D=Yk6J?KBeup8%X2lzq57Sod$%qkn0yAt>e6Lx(T-bOTG;7NT zHf8gZS%?5IN0hP*vO6r#kJ@p%3w~BsI-RXu5;cS#I>NV6HjcyZMSTQ z_!nbbHk*?tBcOpO0arRaB|48S+d)az51KSna5RX|?tn!|8EjM|)@)W9pk8V|SOlik zZXE5=&uZ!NOV%bi&BVrhuX^@8%eUdb1 zUN8Q0@=~9oV6C!_3cd@3NX`%HP76uwHuEy}lSl|o%(I58*?e-9&{eIK8Ic-if`2xN zMnGODdvT-pBbSKW8IUj?Pq#|*9~VYl_`qs8Awa^c`;tziF+)(rmI}G7)FvqJ(H-IY zSa`9pjE6Uk#Z9-pCfOO8T4#rsC&urw^D_*piG?8&xE6^(k zX5%LTZ8#>W-Owa568$*PA(rYKbGq)B@5fnvf(1w24r>|zkKR56o(F`Gpcf+aU9O z5SphcFFJn4$vRwq34Y#^POzv>J9Tyk(LUK>rcJYQh3+=cG3{}Cs7;P-8}xx@BxZ&0 z%Y}EEXyb>$wl2LzdN8UZF0YSiVTzHbyw&xhTdpOM(1YIntb1o~NDj&R&a-eQd_~ebm838V=Vb zikH2SEWIbq41XGrw62}DrWB`)po<$sUx+m=_GN4In5?GLz?yuly{bs%@&wUJx4byyXt-_*n%5_KS9_&$K(`d6gGIUIrs1_3H^tgZ$O;iP6 zxK1WyoS}Sq%5Gq3Aq^Cm3yhR;&KL^GRleQ07R`FSg+_85YVyq(S*3(yU#k{ZdhV*C zJtxl2pa^-66bmv;s8uHiCMENsD4g%6WO9>e@Ws+wmGs}|$TRf~fRQx)P?YL8BMl=m zIiBXPmeVdFT-!SS9hu{__xI^o4pOy8NV6}UMV%sqd%K6zf%luj>LpZXG=_-`b(tR8 zfjjvhh{a7E*Hh(Lw2GFfuiVKktKHpIPq5Y0^++51{%Ssm5wJ@-NNM{(6lmPV69F>CB8fm%v=&zQqEK(mglKR9Z&Lkfc)7 zv}Q)GDW&~3HWA4>)n2i*Nq^##w0$qJ1?%H&m14@|`JrRAgA9}Md}OIQgF+xA&_jhEa164Y(}!;Px- zsZ7c%GM3U*H&VZ&RFyI0%B`17?Of<@|Hd{y@Aoy2E{Ii1qt?kdo1XR5E2=VgHma4>L_g-^BhPM_M@vpKtQGQ=vSQz|Uug8^hsCmXN(%9Y zNGAtpT;o@JP)7-?iZ(Zd_`f;UeZJXiDME>(&I7{S(cD1OW@!ec`qWa#2p?^I?lB8F z+~^JwBXGV-a?Lv~M%UkUOj=ERts)w-NRtw+4G30Q)Q@Z}uE^>XvKpu)MtBE=gp~iT zdS{*r@RxqnU}r;5ua&Me=OeXlV=})^*te2Cj*ohB;+%`A79ekNSS|kev1p^ zW;YevEqI(SWT(g&K@Ns_+1dXrSCMonnv(QSqiz)!*oN6L5cc-{g%T-@lhkUxAaMbUpsQ5QWQwou5H5ejv38G3~QuNx7u&umId0?gMfhwmN-_% z94H5}1HXy|M0i!O4XE{?-H1@^J1^%)$mD*`mX&KqG@#k1k%+ppq`Om0tDteWt%DWk@b~v$8EAm#s02@k#d-t9|b_Ee29FW zt%#2=c=YDI%X^bXOL67d7RpvTG!v|E_!DW3DH^hs6cZ*E;s#ki1kEZH6J>FTZW)e6 zqVS?r+=hw<(Kkv0LG4AH?-U8j0ge04dsR&2XQBT0AD-GMNtdSgFA;pX*pzj$ zRst#E6e)}R!N}%Fjzl!s{7YcsYYuB_cUas9bOH*4o@O( z&xD(es(aa_Eu*&21b>aMrUlF8xOGj@L=U$mkH3!1`b^%{v#6Vl0eAVFHgm-M{`t9F zE-d_qmfhRa4?V;}F)0FsC@z`~c>kQGNH;2PTgxsIKt)hZQY=uI|cYx1-SfK1%6dqX2)qVXnIDvZ?srx7_R!2(N zL5~;(K?@L<&~y<5(LG4*3tJi$0w^7NS&`w~SyU@*yqOtxZQNfcSaSwVjIxQ2mNp+O zHQ%5`GX;HpF{tjhs#8iDh)q6uSWJC+#n1)a%uc42p78tZqpWF6R7LW$`qNo_d#_pk zp(;EL(LNaN`oX00-~fwv6q`wCJM0kPBYj2Rgf&}hhos+HrNE%0xLzkrWgv7kQ!Ip* z;RoRAB%T_DYm`_Hjy4f+n#qvsp!{lde17~2KO zwowGCysjvY>zJ8pJ-@V%r{+lY+?QB^P z*}DsssXkrRAo~vAfprA0vz^s2l4{`M3P>8AodlRL0*8?fpi3_#gcM-@C?5A?(%Wnn zVNGn+c z$RE>R@jGW2D%L;0#{LZVh(Ia+%R(w?>`X(<**}|B9lZSPA5Y=u){CT;BH4|nFipC3 zRZBSEc$KIbdE>C>0(3D9J3MJY>smpwx)0_Q0`5C)d@I8x_PlBc5s+50D6|l5@B`UE56}kI}OBqahN3euu2tC7R#y z5rvmNohG0+p3x|7)U~fWHGPFQroxl* zQKb&)?Uw%WR5_NB?dLVD-7#{E;_?)PRkgIVI%0YJUAjf7hTt?AfdjeJc>(6#Ntk=M zE98e5AqXL}fP8NFH=!hrQiK)ALj9H|N5u`n%A@yaub6ek3+A^K^{ce*+@YD@Mr8Ho zwGn_tc2(MdDNFUn`@5B~v0}81YkS*0(!&Ub0GPEky?@I;ZRq*)FghL-60Z z*r1=wENy5FLcjoLQf^lGRXCfhr|?DZ_BWH9Aqb_NEr#Fj*o7 zA13sl)M`g5b2daWnq5?LPjWwh>C~jrp4aIid#Po#0%Piom)G_LCCLbQ3{87eWzC7u zu0Xly3L66~dXel*@4Mi4QS(Bb$*x&*hK`y#7cRgMT)VO^@Aq7I%W$WFr2#xAJh&KJGS~H6@+3e|q z_|x-65`cBBMH?-hYDDq7SCL3%kg=m>ETSpgO)q^9+r^3Jc@qq#f5_0NbZU^8NuiJz zGGOCh2lopT+MpBeHSktk_5b?D$^`&uwK3X5FKmXpI0g!x=_s`jNIcd{f*6;|DT3w6 zP`Al>c^zjarL1r;zfj7QE7F%!Vt!&p(*&!Nd5dsKe0JBA8Il99ZoSi&{miNkhocZO zpUb)SrZll?CUE&IZ9i!!S@rO2JL2<{p^jf)9LO*b@^aF!4d^BT#;qK~Hn4d78KjaN z+m8>usb$4}$KEY}Hs)L%?{_C683vS@hZLvduWqa~LtP%ZAS)v?9IB+Mok(=P#PQV= z_HliT(~i9TS3|2z985jJo#f^Z`@&QNS5#K7pk0L?*Vm~QBcE_{(5jVQ-Cx=XtDqC0 zD0Pp7`1_*tHYX|9T+Y}doqqf(Oi8Ol#5$Obwze35V?&hpHOGjhH@3~=9$*yaW~s=m znyx21Iy=S2=7%Ke!~qOOG_e9ezPaHd01M*Rq=gR|~9V;lO4 zl(<-R0A+V!`8&xdlIKpJlRg_8s3N@vK$ot@N!dxrBtPT4Mm3rIhs7AVnM@OT|78v5 zm5}8$AQ!A#3Gajk^XL405(V?0eJAtvhFSVr@8y)SvNf+W5~9|l1lwj68x7{=!WpSm z*g?HbsTc2yrGM{>Pxn!v?DK@M|74QB#IKYo(N-;D?UT52e1}NmvyX=~a?v#OZ@)sD zOK~MlM?3?q+P7qxF-n%TepWG(j7NX4?F)WXq3K)t3=KouMMC9*NP6|9a6g=&-kZt3 zfnEeVSV<{&4-M-@jy2+DTaB9HeXcInsWsycZ}U21O&sk*JS;=yr?;JlfDrf?xZxF2 z7+;tK!0kBa*eZkt)c*EwecsTfd3}v8G!?Bh910{X{rcf1qlC#HJA~*vW7(Wj4)Z`qIyKL>xg+h{sYLHCAZt|MIFtAzJTa zNHq#EA$%hHj=r} z8dHm;1!Du9_JUoO;!c~-qUoG8jwrk`e0DWXj95S2L!#0_j4Mt;h|D@9@p`=2fvh8? z0`0-Y{oZM!j1B8W*5{O}-AAZ966q-tu=iZ841SWtzKT}t1Xm`VU^I&%+N{#g)b{4e} zUu@v)#|4X`O&X)8J1s^IX-SjGw2bhy0OO=g zk#Zb(*0MU*YH1Xpv|0kc&kMIfj znKa=hgSiQ2frB0W>fcJ0Wt6C{d`|QAu_{*Y2UK*-yeZ!4lzGQSuTG9J+~)x;O-*xf z{>t~c>4iF#y6bE-!#UFqkS$)`Jj|u>{fLcK=*?Thu?XqNoRko@qV%L$G<_^+G|3q| z3)7P~n-%;}IJ4S@5DW-IR_G3J>p{@w)`-<9_6~FCHU+%pjY`8X%>O~CYN~}`?5dNG z=ZJ16T{x!@knyoklr2a4SED=X9wCzQS_Nrx_XOUIQ5&s(q}3cRPbU-S9auE_*e4_) z_tsIf#@S=9CcO#+9o>3D8h0^T=mKxA`FTa{G1@Edr?$Gs4KV6xJ8=m&zfp&W*-y)g z3>9iRc@>kBur`e0-wDlsCgaXW&_>xQf08YzxhE+TXM^iDT%?7Ef8Z*0VRmAn=$!Xg zArkZqyY%I+weukoj_bs0X2`tzTm@5ameBk!;R21?u;uHeQUaA)ZfvyGIaTW>dZK8; z#+WS`J}FYn-jh1(jZ(L*#DYq(dXsRz*ELS}XY` z#z`@9DU|ZswOKu+N!}i|$C_9q=)*oS|FcO>-ILr=52?B%{HFaEyoHkA7mjbPDLwLWB3Lovl6AgMYgEd@30l zFUE(6E{o3^bXm@xu`&I{2{#*_$d*<=X2AP(SkzDAt?rWND9y3&_Snmbj~NjZLyz3E zHu+P`V2VNyTCXZqj<#a#f4NOhtefj{u{psnls3ui~WuH5+{p{O%9zVEPGY!aC!1egAm%3k?7RDSUeWw2c3}=SbLeC{3-) zU474bb`U^GJxGQtfMU5!-2^t%g2!1N>~00&mpl2S9qfOc)-#^h5Y&T!fM5s$EzOn( z^NL;etzh>hPkN1t!I(%lCF!%{5bl}@2^RfH;zSv05f>V+?Y(RN^Js;UDTU^M6q1O% z2%-s%uzhg~irI{nzq>oFB)7+!xihF67nRu-fZ=}-Qk64B{K-(Au38W={%JQDLc6iX zOad{0M&Yv`H@;`pch;>0fON;qkFSAi1$bFgzy$5O#++5RwD^aDUtJ!p;_|_l(rl$K zDTD@l2=Hx^MGpX)TUK%=^YnPr!j$H?U~lG2(zdo`kUex`7Dp>uhwtHQku#oHckXI^ zM&(#cDeQq>zzlK_%#4V{9pTUfH2#aNeX^7=KB(`!tQA75RHRoMT>+90XFTFE90`ecv52OnkQ~tIO;U`bAZU z^vi^l(ABR<2e+7-xTzwHAF;nzaDo%n9b-+Z)O~ndJZxTow0RKnJb%Ld4YGfl;t~LkrONCWq&5L**|(9-CL>YcV;vhoCe0aD<|(D6$0@M{ z?a>M&)Cno8rz89^#sq^@H{A+ahRs({D!shCrVb4p`suICroB)_wmxy5jW8Hdt48|J z!C0-`g{}l|pd0Pj?_7~eA4`DVrqsHN=*Zc3>m2CUK1Z|tK;--UV@#hEccMDi%LMSG3xeX5@Tt+y4n?DLK*O= zejf3Sc;TCD6rpzA_9)0RIkyb!!M7j|$W|t@DLT-}RA6AHi)8=q?w_{cE^U8Uc;z?+ zG*6LG*-CM*umbV9xBP#}6Ki=H&&cJb))W8)U#8N`f$rP-KUlW@1A$ z$Efxynt&MO1Nu{5`l|;Rn~zpUZqhs(&$G%`%NW)<;T?6pG||cc+EdT~SToXn>b0(n zrAbRs;8jEvn~*YJP9YzX=F@&K?YlJ!El6<(*V3m=xgZqsQEx~Ysj1|F{XSKTO(PCf zpROy&E~@kmms#9>Fi@U8unUL=f_#*Zl|j)HsUqbnMk<_&=7@Bt>?@?_*ZSDhAxfR0 zrf1yju}>WBBe@)NNT7-7=~uNdgYv+L`Ds!AVmNG+(i0Pf;)vti_gO#;38cVYFCNs! zM%YS;N+&LZcKRLBVaBrg8zw-LI7>I}!PFBqAHX9INgz{G?}07oj1UxzaO5fMaMz)_ zx;d^NWfsW$RpsqGG@O==^Vm|bUEm7rIVU}45qAn#bPk245@Tl!N}grJn0&bK;W9uQ=260=*MK0-zPOfI(80{+kj5|s z0>u%>{mIA{)woF{RACvnC5v*{LXz7g`1^ae!rQB^XQ z5bu3N_h!VIQuUV3LuMv85*pLvUX~A7qQJRMJg5~BtyJb}yenF#t?+~tx>p9nuhJ^i zS1KX!_0;wgt)RLu%7^V+<8Z;7EAIrQD`Z5{s_twqh@V{GUYk0OEQd=U7-2M4W6%!!=Fu-hHu;Qj{Zqp)E6g6|w#Sz}m2TW@$$ zr!AXCdY)1p7u?Mc_DYDY`aII!;~)aE_)P3=tl2(FE8a0siA-$mxYNulh@)mbdG+)H zNkDi-Pt~h54BSU;oc5a9v-@FG`q3$k0(;?Z9eS^-ae3I8j2hiuUGyc5`vJJ)WiEDA zEH`sOb>(_8!6o$@h6>`KDvFyBKdRo8tpa7a>5ch!R*q;}l_Pw$M5cQ@n7e_Es6t$q z1#_e}OW(RUA)MEeVEubc6rMeMnTwy?y&2nIQ9OF)jzJ)jYUQQ*d4*j5vH2;5j2LQ` zPyObgZjj{27RQ)F-AbbSj#>^K8bP8n14&Z+3+9WcQ>zy0B3&di#TaL^oh51J^{jKC z@ltOd@Dk{$3|+X0DsEm4!9}BHxL){sYBQ*3gPrNG9E5YuMO%-I3rZ{9n13dL%4^ho zwByUDq(|eJ12`aM>C=N9RKbu|7Q+R}v1$qrs~kkcz50p5@>!?1z*pWq;o7cF-73Ks zahO$@_~ljc7+qJ44C!9B|bA^a#HoT2`S=I}ld)TGK+J>xI7yGrfjvwpbk zMT6Ts2dP7%n_E1*WP&U`%0+ zTV6gKdurnxUb1&q*C1P{r*9>V#t=^mHBt3-Wy57;Ns029N>$4XEyftnaYFNtrU7KK z=)gqlEv2BiQXiLX*5fX5C06|pl*y>r)@_(R=Q_fdPNYzC6fQU&rlW1`h87#H`lKLw z1Umv_(HqRx!%G#O&X_%x*L0S4wQR%IZ~%j=fJ$p3}0vTb{gm@if9 z8gYN>z2}Fh8E=zQ)Mg~kE0Qa8^RQB0O|!qF`dHey_#=7pK)`*Rd-87O%lU7H)pJs) zc53v*oLv1iWl48fjbwxAvOj%Z33cN=IIaUAvC}Ll%BilGh1y`pYr+0fNZ8uh7J0?& z0hb73;WS4tF%{POun4D$wH<|w?8l4R{EIO`wFYsnvrboME*~`-zzXkRrJORx=p=3U zX#u3!bDJ{$Pm`H#Do&3@LK0&iLNo8ISXswKRCIgE;WW1Uq^hLkqe+*{uxUoeOc_SK z6#I%Odt9JjPtihUyhb%ZuRR)03zTjbl5XA6fO1oT@DXWgd|9izn+Zduuv@CRyn1%0 z)lN1|n%e+%lxbW9WlVsNM>=2Mx;+kgUw{qh78Y1k6FIr;mcv~P`HyYz5iIGYIOqU6 zb0j!ZtbHk(GRS!rpY%o6hK)YZ%cx+TBvZ)DSHK}udp7LVSdmStu6f0-_A*XUR{#!< zeb2R0iJ*eIS+`HaRKqFKbzysP zfBfQ+&`x2;3#5VmLWyS-kn)fbzpZznw>H_{$f6Hxv2?8Llo#rv3AWSlQbCc7(YzRL z;l^x-xGc!QoV`OM3P?vkHv@$az5TOQV||!Ov{YD0*b&ZUAN3B z%?9o>MkadN3NRb4<9j8Dtr_xyM5LF3e(in z@`bTfB58t5lndqcKI z(fO-bmBz+*Zw(!fc#H)_#?76x-@!U~A!P%EN}0(fZ_-@a7Jr?Zc(ya%ZU1doF{kRK zWsOA$6gskHgq)iHa z0vD}zn)FnYlx=forw}U0{261MeDyv-m2HLBqZtyrkJ7jB5RW;52BL_``hnG7$XP#P zRyO=r$}EW2P61mH)q!s!s;@MreYn^cL>`STyJx5^*U8JUESZx`59i-h5?+&)4)hU1 z-|8H}yHAN`o=$C3fkNo|62m&?HGPUZunV91uJsipj$^mtPa8SBs@m39QDBj{NBk`{ zmW*EDg9ZzlP;GR!c9;_)^11GhMJ(T(%G??XkTM!eA?ItSOdGd-F=Fl1xYsf##L4N5 zC&XhP$b^atjr(spT{v@wTtW1KpnSQC0>Lzma^Rbj3$wWTJZMF)7ssdr!tziWwm+T` z@+_oPr?>e)z{vJdcE-fE_paz6%|!q4*Qb$wi7L zIy!r=t=~onW8I_>2nfS?kpJhaEw2T}-0xo>e$gJoJ<#A!Zo#78mJ4p9QgzrY!wBhc zp)*whrFg;r4e*87J|V9C7x1+|-lMAXj!mtG$ZSR zt5HO4Xpn9u6(OL2NTdN15me?WVGx=0Q*kz&&)#R9wbnjE&pI1Y9hLFe z04VFcD)Ju?mpSacOF#*N5THAuvv^8;T<1{wu^X0yc~4$@gxb#Z&HXpz4$r5j{P|!h z8RFg{wnMNw?bjQqC-WFlWDB%LF@|-&>r0b4zcnv@1o*;IfL9HUv8OH6v%*rUq0Pcsz!R#-7a;3hoQ>+TcQpQ;?8X&-Vv5{%@+Nk(QDM?$o|gOS?)x;n>jB@{w9&5C*}})d+7;3^m4#|TgkQX7q97Jfv=T*t z@YuzK_zkD;v$uT)zuWRtaFBxW1UOY&h1bKVvzMhZTqCl=Uk49N09ENTXoJH+XV&g)}JS z-F^erz;Jy_1wSJLdN2ZUMf>}AMY3+)A>_ryFFlKDk-2i(9=?d9tntC>hW}7nSfm96 zT2+jidOCrHqa9l6xRURppf6)#7Exi;LnjG_V(_yKk3iQ@JQ;zxKCCptGC<&mUP*yr zN%MUUwb@3>+G%NnE|5wzX?ZDuVUj?D!S2GCniGs)1K3SaMD#)GkGlX8W7@TyEa1y= z**Jz>>&XEZ_ftNIG9>SYQ9Va~chv7e2KO!Ut~f;u=a2~T0We#o6F-p_#sO8F2ptD% zOsLyXr4q@Df=CV4lDr+xD{!d+4rXWK*C~#{lWR+%^G!)NifYCS7$C`X>%Ioa2I5KQkx2Sn)fXw@a^Q@B%H<8-FWScnmB;B=TIv>x17}9PMDr>GAIbP zyVHo`3pO$0rGE-9#zg>hc~S12UrF?XCZh(BaNV+@d%h1St^S-*WG%bhKkSmiQ<-NY zRo9x#h1GY6;MFKsZsa&b4`|zsMDCQgBphi2KzM?v5#-Q(16M0J;DS9u)TnK#(|MFD zW-sE)lkTm(DTrZ8UnI?TA!M80WCU(NnJT};`MwE!(3qkXr77=#e;$e)0sw(?fHGQl zNck1G)P~=;5NhxnDx_uRza>@7?10v6dQxlHASQ8E%R`-kHV0v{+`lL``hD{Nlm-nI z|6=|Jzec^3y%-F3y;V9Q1Sz<83Uwh&`gG0giJ3}iB6pf9W)2#?Z-i6q1N#bzFXo?E zD;Aj?!Uiy^eHd|>FceH#S4-?Mqh_Fx)pVR6W&=~MS2OY~bct}uw)*MI-`NGlP-^6#L7pXmAffs7~)E5K%&p65j!N`$#3D+ps&W6ZC(x0$Yp96dZ_^{~LJRzi92;*%>JgWVUp!2~ z$-66_OpN5@(a#&#xY}PF#hhx#`Mb5VjCR}LlhT!}P%i%lo^m!S#L_8SrRXi>W6mm8 z7dmK@Y{%^P&CSvut#x*NslZKP*4n}5SZoYvQ6p9T+s$`evr<^dq1KyLAL~q!7z(tM zy>&&V-m@Byb8v9DMbR(bMQ9s6Y;myK3x(5x27Hg*D{o8KOYXD^AsnDZTQ%_|+jk2; zp>;jD{S8jN{X-_d_vMew)EjHQbi!Y{WDh6yUU-!fuY-+U4%VfyxI0M_r?Xg^fx_R= z=vo`wnzf3PE6xDAWb65$`vL!Xdyvz3(FfAPo1U4^zl2H6;Zw(1X&y7#9c&twJ$Q5c zr$@-rsil={v~k~^F4QZIJnhQP#OrKF9eV1cnG@w3AjN~xCcuzyYAF2dd+Ya?^T z(xW+y>0yB(OV9F!h}s;6(dUPHC0riKNyBn$OQs#`j{4UH5x0D-Pi?4yB_Uc4;cUsd zKYYUQv5Il`pQ82FtyGzt`urA?WEGPG$5;A+W@gHQ18%aWv{@4%CHXK0Y=M-t_$zbT zwJmv_8Y$Q%=|+lXI_Db5=4piSC(ZlEy*5Cvm zH+qXRWiMnhW)7m;!;cppe^^S);A~_VCT6(y5$1%$QPl{ZbTmcb+oGdds6!a(JZhZN zlLw#B=vh5(z*vtraD{Kb#R?muDWdN8f}9eg7tJ`)D-yd!*IF{@Z;(=b^IlF$W(Gcz zN@!>uMagq(b7o3ok5`v+tohTt@VUMsHBU3knP+#*n2`=+$J;5X{of6Kq3rO6u{U|X z(Lu+Z_#sQ-9H{qQQI%~;ynBV;5q_A|U-TB`+mTlh4$k3FErQO>Hx~R+&+#7yiTJ&f z;Zk#Uc?YqHS6j@gBM-l7xM<%tf9_70B7*1lvX)fM>8<1lQm`<_gU_0aww9Wb=^shI zyN|N6#bG7DNb&U8G#m6=+yy%d(RDr-ouNhRCpYmj^}m$p^jp1gtqwtbTXrr!g-CD0 zi2`}MAaI9lpVorK3Z;gPZFasfxJm!LtpP!D4F)~k>&584Je#o$(Or}HbrUnZ+g=q8%B z4kZp&`0+3EeH+J{$_m_=A^67u>D5FrjE-9jrQX^z?wn7lIWPOUr$Et!mtAQl6>(wb z&PL&k*~f521>{B#lNaX?d)~Pj;@hZ6=WbgWR#C`vpg{Pgjc*5aDr}KVZE;JSUIv0#hDHWyR zYKZDB)1zOZ`mW23Rh3$_uq|ALiNf!@p-Hm=9+fCSBX`iCV8*5h%b)+0rvJ=gdP^$n z3bt^wOG~bb$K;Aru4_s(4J55AXEL_Xd#DYm`m>%h2V;6H(D=#iIs<%|hUa}Q+of}Cv467_X`ek0TIO8q7+v(wZ z|A~S-2{~SljXyh0mDIXpUmYITBRR$hMnCRoMmHeY%<3Uhu8%;_dr$d$=;I6XhLy z`9GvAj)n(;?}1ZbjFqYm%XR8#S?zT&!~IV z-V?IrP)K{*$;#8Da~km5Z^PDjeT%M|WDbhPZI5g+9O{il_%z8Y#W9<;Od7c@zr^Rh z1SmtZAlfLSY?U)p=9%qb5hB#rFAa zl2LQF#dOwa++P1uWeO_gDp?#R%5_o7Ph;m2Ty=!|jlQ=B!B$_^Yz@s%|C-D1ODIuM zf=T~Aii%8`pL~{tk(7En*@1O8{*j;W<%`AIL7D0jK9(lf{)LtA9#%50Xd|>FabRbe z)Cn*KhZBnZ&JBR#HPa*Y6gQ+_1J;%7Fv-ozOt(t1ncp&mrIxRjJlU547}I@XYsjO2 z{7nb+NOL`AOt|*nfE^34iTHTpAK1&!0QMMG-ts`fpg~gl_cvf-MJ|7{hB<;o4W9@> z|NZ}>0l87PXT_T@2f5Z?H3#9(xp!#UWjAnjKd_-Ty67$Elf4J5DB(pGemN{-0l3oU zqiTe|e*hB|C4kAkUiRxCe2oO;!TS0*d>w>8mh=CAkx)2j%!59)1IE^${*osz4aO>T zGEb!xKuy&IAA@D-12IaJXKsqqJinZ-x^wmV{^#G=-&>y9WFX-=7Nn^EnG=_?mOU()sEwMXsf3+Qob; z<)`AyW=l*WfAd{{QPZ^JDNoY2eGpqV@hV0!9Mz1qyz5Q3GMASb_zf0{x$K}uyefVD z|L`p@zp+xttO;^AN(4;YJM-fbn&d}OkB1Yd|4i_ K+s`yT68m4dwC~dZ literal 0 HcmV?d00001 diff --git a/controller_manager/doc/userdoc.rst b/controller_manager/doc/userdoc.rst index f5e962047f..8f00bef4b9 100644 --- a/controller_manager/doc/userdoc.rst +++ b/controller_manager/doc/userdoc.rst @@ -148,6 +148,22 @@ There are two scripts to interact with controller manager from launch files: --configure Configures the given components. +rqt_controller_manager +---------------------- +A GUI tool to interact with the controller manager services to be able to switch the lifecycle states of the controllers as well as the hardware components. + +.. image:: images/rqt_controller_manager.png + +It can be launched independently using the following command or as rqt plugin. + +.. code-block:: console + + ros2 run rqt_controller_manager rqt_controller_manager + + * Double-click on a controller or hardware component to show the additional info. + * Right-click on a controller or hardware component to show a context menu with options for lifecycle management. + + Using the Controller Manager in a Process ----------------------------------------- diff --git a/rqt_controller_manager/package.xml b/rqt_controller_manager/package.xml index f1d1495286..2972336cbe 100644 --- a/rqt_controller_manager/package.xml +++ b/rqt_controller_manager/package.xml @@ -12,11 +12,12 @@ https://github.com/ros-controls/ros2_control/issues https://github.com/ros-controls/ros2_control + Adolfo Rodríguez Tsouroukdissian Bence Magyar + Christoph Froehlich Enrique Fernandez - Mathias Lüdtke Kelsey Hawkins - Adolfo Rodríguez Tsouroukdissian + Mathias Lüdtke controller_manager controller_manager_msgs diff --git a/rqt_controller_manager/resource/controller_manager.ui b/rqt_controller_manager/resource/controller_manager.ui index 2ede975248..17031d9044 100644 --- a/rqt_controller_manager/resource/controller_manager.ui +++ b/rqt_controller_manager/resource/controller_manager.ui @@ -37,7 +37,7 @@ - + 0 @@ -70,6 +70,40 @@ + + + + + 0 + 0 + + + + true + + + QAbstractItemView::NoSelection + + + QAbstractItemView::SelectRows + + + false + + + false + + + false + + + true + + + false + + + diff --git a/rqt_controller_manager/resource/controller_info.ui b/rqt_controller_manager/resource/popup_info.ui similarity index 96% rename from rqt_controller_manager/resource/controller_info.ui rename to rqt_controller_manager/resource/popup_info.ui index b8c03799a9..b910397a8d 100644 --- a/rqt_controller_manager/resource/controller_info.ui +++ b/rqt_controller_manager/resource/popup_info.ui @@ -16,9 +16,6 @@ 0 - - Controller Information - diff --git a/rqt_controller_manager/rqt_controller_manager/controller_manager.py b/rqt_controller_manager/rqt_controller_manager/controller_manager.py index d142ea847b..3b4a9a7de1 100644 --- a/rqt_controller_manager/rqt_controller_manager/controller_manager.py +++ b/rqt_controller_manager/rqt_controller_manager/controller_manager.py @@ -20,12 +20,16 @@ from controller_manager.controller_manager_services import ( configure_controller, list_controllers, + list_hardware_components, + set_hardware_component_state, load_controller, switch_controllers, unload_controller, ) + from controller_manager_msgs.msg import ControllerState from controller_manager_msgs.srv import SwitchController +from lifecycle_msgs.msg import State from python_qt_binding import loadUi from python_qt_binding.QtCore import QAbstractTableModel, Qt, QTimer from python_qt_binding.QtGui import QCursor, QFont, QIcon, QStandardItem, QStandardItemModel @@ -60,7 +64,7 @@ def __init__(self, context): # Pop-up that displays controller information self._popup_widget = QWidget() ui_file = os.path.join( - get_package_share_directory("rqt_controller_manager"), "resource", "controller_info.ui" + get_package_share_directory("rqt_controller_manager"), "resource", "popup_info.ui" ) loadUi(ui_file, self._popup_widget) self._popup_widget.setObjectName("ControllerInfoUi") @@ -78,7 +82,9 @@ def __init__(self, context): # Initialize members self._cm_name = "" # Name of the selected controller manager's node self._controllers = [] # State of each controller - self._table_model = None + self._hw_components = [] # State of each hw component + self._ctrl_table_model = None + self._hw_table_model = None # Store reference to node self._node = context.node @@ -93,16 +99,26 @@ def __init__(self, context): } # Controllers display - table_view = self._widget.table_view - table_view.setContextMenuPolicy(Qt.CustomContextMenu) - table_view.customContextMenuRequested.connect(self._on_ctrl_menu) - - table_view.doubleClicked.connect(self._on_ctrl_info) - - header = table_view.horizontalHeader() - header.setSectionResizeMode(QHeaderView.ResizeToContents) - header.setContextMenuPolicy(Qt.CustomContextMenu) - header.customContextMenuRequested.connect(self._on_header_menu) + ctrl_table_view = self._widget.ctrl_table_view + ctrl_table_view.setContextMenuPolicy(Qt.CustomContextMenu) + ctrl_table_view.customContextMenuRequested.connect(self._on_ctrl_menu) + ctrl_table_view.doubleClicked.connect(self._on_ctrl_info) + + ctrl_header = ctrl_table_view.horizontalHeader() + ctrl_header.setSectionResizeMode(QHeaderView.ResizeToContents) + ctrl_header.setContextMenuPolicy(Qt.CustomContextMenu) + ctrl_header.customContextMenuRequested.connect(self._on_ctrl_header_menu) + + # Hardware components display + hw_table_view = self._widget.hw_table_view + hw_table_view.setContextMenuPolicy(Qt.CustomContextMenu) + hw_table_view.customContextMenuRequested.connect(self._on_hw_menu) + hw_table_view.doubleClicked.connect(self._on_hw_info) + + hw_header = hw_table_view.horizontalHeader() + hw_header.setSectionResizeMode(QHeaderView.ResizeToContents) + hw_header.setContextMenuPolicy(Qt.CustomContextMenu) + hw_header.customContextMenuRequested.connect(self._on_hw_header_menu) # Timer for controller manager updates self._update_cm_list_timer = QTimer(self) @@ -116,6 +132,12 @@ def __init__(self, context): self._update_ctrl_list_timer.timeout.connect(self._update_controllers) self._update_ctrl_list_timer.start() + # Timer for running hw components updates + self._update_hw_components_list_timer = QTimer(self) + self._update_hw_components_list_timer.setInterval(int(1000.0 / self._cm_update_freq)) + self._update_hw_components_list_timer.timeout.connect(self._update_hw_components) + self._update_hw_components_list_timer.start() + # Signal connections w = self._widget w.cm_combo.currentIndexChanged[str].connect(self._on_cm_change) @@ -148,6 +170,7 @@ def _on_cm_change(self, cm_name): if cm_name: self._update_controllers() + self._update_hw_components() def _update_controllers(self): @@ -191,20 +214,20 @@ def _list_controllers(self): return [] def _show_controllers(self): - table_view = self._widget.table_view - self._table_model = ControllerTable(self._controllers, self._icons) - table_view.setModel(self._table_model) + ctrl_table_view = self._widget.ctrl_table_view + self._ctrl_table_model = ControllerTable(self._controllers, self._icons) + ctrl_table_view.setModel(self._ctrl_table_model) def _on_ctrl_menu(self, pos): # Get data of selected controller - row = self._widget.table_view.rowAt(pos.y()) + row = self._widget.ctrl_table_view.rowAt(pos.y()) if row < 0: return # Cursor is not under a valid item ctrl = self._controllers[row] # Show context menu - menu = QMenu(self._widget.table_view) + menu = QMenu(self._widget.ctrl_table_view) if ctrl.state == "active": action_deactivate = menu.addAction(self._icons["inactive"], "Deactivate") action_kill = menu.addAction(self._icons["finalized"], "Deactivate and Unload") @@ -220,7 +243,7 @@ def _on_ctrl_menu(self, pos): action_configure = menu.addAction(self._icons["inactive"], "Load and Configure") action_activate = menu.addAction(self._icons["active"], "Load, Configure and Activate") - action = menu.exec_(self._widget.table_view.mapToGlobal(pos)) + action = menu.exec_(self._widget.ctrl_table_view.mapToGlobal(pos)) # Evaluate user action if ctrl.state == "active": @@ -254,6 +277,7 @@ def _on_ctrl_menu(self, pos): def _on_ctrl_info(self, index): popup = self._popup_widget + popup.setWindowTitle("Controller Information") ctrl = self._controllers[index.row()] popup.ctrl_name.setText(ctrl.name) @@ -272,42 +296,186 @@ def _on_ctrl_info(self, index): popup.move(QCursor.pos()) popup.show() - def _on_header_menu(self, pos): - header = self._widget.table_view.horizontalHeader() + def _on_ctrl_header_menu(self, pos): + ctrl_header = self._widget.ctrl_table_view.horizontalHeader() + + # Show context menu + menu = QMenu(self._widget.ctrl_table_view) + action_toggle_auto_resize = menu.addAction("Toggle Auto-Resize") + action = menu.exec_(ctrl_header.mapToGlobal(pos)) + + # Evaluate user action + if action is action_toggle_auto_resize: + if ctrl_header.resizeMode(0) == QHeaderView.ResizeToContents: + ctrl_header.setSectionResizeMode(QHeaderView.Interactive) + else: + ctrl_header.setSectionResizeMode(QHeaderView.ResizeToContents) + + def _update_hw_components(self): + if not self._cm_name: + return + + # Find hw_components associated to the selected controller manager + hw_components = self._list_hw_components() + + # Update controller display, if necessary + if self._hw_components != hw_components: + self._hw_components = hw_components + self._show_hw_components() # NOTE: Model is recomputed from scratch + + def _list_hw_components(self): + """ + List the hw_components associated to a controller manager node. + + @return List of hw_components associated to a controller manager + node. Contains both stopped/running hw_components, as returned by + the C{list_hardware_components} service + @rtype [str] + """ + # Add loaded hw_components first + try: + hw_components = list_hardware_components( + self._node, self._cm_name, 2.0 / self._cm_update_freq + ).component + return hw_components + except RuntimeError as e: + print(e) + return [] + + def _show_hw_components(self): + hw_table_view = self._widget.hw_table_view + self._hw_table_model = HwComponentTable(self._hw_components, self._icons) + hw_table_view.setModel(self._hw_table_model) + + def _on_hw_menu(self, pos): + # Get data of selected controller + row = self._widget.hw_table_view.rowAt(pos.y()) + if row < 0: + return # Cursor is not under a valid item + + hw_component = self._hw_components[row] + + # Show context menu + menu = QMenu(self._widget.hw_table_view) + if hw_component.state.label == "active": + action_deactivate = menu.addAction(self._icons["inactive"], "Deactivate") + action_cleanup = menu.addAction(self._icons["finalized"], "Deactivate and Cleanup") + elif hw_component.state.label == "inactive": + action_activate = menu.addAction(self._icons["active"], "Activate") + action_cleanup = menu.addAction(self._icons["unconfigured"], "Cleanup") + elif hw_component.state.label == "unconfigured": + action_configure = menu.addAction(self._icons["inactive"], "Configure") + action_spawn = menu.addAction(self._icons["active"], "Configure and Activate") + + action = menu.exec_(self._widget.hw_table_view.mapToGlobal(pos)) + + # Evaluate user action + if hw_component.state.label == "active": + if action is action_deactivate: + self._set_inactive_hw_component(hw_component.name) + elif action is action_cleanup: + self._set_unconfigured_hw_component(hw_component.name) + elif hw_component.state.label == "inactive": + if action is action_activate: + self._set_active_hw_component(hw_component.name) + elif action is action_cleanup: + self._set_unconfigured_hw_component(hw_component.name) + elif hw_component.state.label == "unconfigured": + if action is action_configure: + self._set_inactive_hw_component(hw_component.name) + elif action is action_spawn: + self._set_active_hw_component(hw_component.name) + + def _on_hw_info(self, index): + popup = self._popup_widget + popup.setWindowTitle("Hardware Component Info") + + hw_component = self._hw_components[index.row()] + popup.ctrl_name.setText(hw_component.name) + popup.ctrl_type.setText(hw_component.type) + + res_model = QStandardItemModel() + model_root = QStandardItem("Command Interfaces") + res_model.appendRow(model_root) + for command_interface in hw_component.command_interfaces: + hw_iface_item = QStandardItem(command_interface.name) + model_root.appendRow(hw_iface_item) + + model_root = QStandardItem("State Interfaces") + res_model.appendRow(model_root) + for state_interface in hw_component.state_interfaces: + hw_iface_item = QStandardItem(state_interface.name) + model_root.appendRow(hw_iface_item) + + popup.resource_tree.setModel(res_model) + popup.resource_tree.setItemDelegate(FontDelegate(popup.resource_tree)) + popup.resource_tree.expandAll() + popup.move(QCursor.pos()) + popup.show() + + def _on_hw_header_menu(self, pos): + hw_header = self._widget.hw_table_view.horizontalHeader() # Show context menu - menu = QMenu(self._widget.table_view) + menu = QMenu(self._widget.hw_table_view) action_toggle_auto_resize = menu.addAction("Toggle Auto-Resize") - action = menu.exec_(header.mapToGlobal(pos)) + action = menu.exec_(hw_header.mapToGlobal(pos)) # Evaluate user action if action is action_toggle_auto_resize: - if header.resizeMode(0) == QHeaderView.ResizeToContents: - header.setSectionResizeMode(QHeaderView.Interactive) + if hw_header.resizeMode(0) == QHeaderView.ResizeToContents: + hw_header.setSectionResizeMode(QHeaderView.Interactive) else: - header.setSectionResizeMode(QHeaderView.ResizeToContents) + hw_header.setSectionResizeMode(QHeaderView.ResizeToContents) def _activate_controller(self, name): - switch_controllers( - node=self._node, - controller_manager_name=self._cm_name, - deactivate_controllers=[], - activate_controllers=[name], - strict=SwitchController.Request.STRICT, - activate_asap=False, - timeout=0.3, - ) + self._switch_controllers([name], []) def _deactivate_controller(self, name): - switch_controllers( - node=self._node, - controller_manager_name=self._cm_name, - deactivate_controllers=[name], - activate_controllers=[], - strict=SwitchController.Request.STRICT, - activate_asap=False, - timeout=0.3, - ) + self._switch_controllers([], [name]) + + def _switch_controllers(self, activate, deactivate): + try: + switch_controllers( + node=self._node, + controller_manager_name=self._cm_name, + activate_controllers=activate, + deactivate_controllers=deactivate, + strict=SwitchController.Request.STRICT, + activate_asap=False, + timeout=0.3, + ) + except Exception as e: + print(e) + + def _set_active_hw_component(self, name): + active_state = State() + active_state.id = State.PRIMARY_STATE_ACTIVE + active_state.label = "active" + self._set_state_hw_component(name, active_state) + + def _set_inactive_hw_component(self, name): + inactive_state = State() + inactive_state.id = State.PRIMARY_STATE_INACTIVE + inactive_state.label = "inactive" + self._set_state_hw_component(name, inactive_state) + + def _set_unconfigured_hw_component(self, name): + unconfigure_state = State() + unconfigure_state.id = State.PRIMARY_STATE_UNCONFIGURED + unconfigure_state.label = "unconfigured" + self._set_state_hw_component(name, unconfigure_state) + + def _set_state_hw_component(self, name, state): + try: + set_hardware_component_state( + node=self._node, + controller_manager_name=self._cm_name, + component_name=name, + lifecyle_state=state, + ) + except Exception as e: + print(e) class ControllerTable(QAbstractTableModel): @@ -361,6 +529,57 @@ def data(self, index, role): return Qt.AlignCenter +class HwComponentTable(QAbstractTableModel): + """ + Model containing hardware component information for tabular display. + + The model allows display of basic read-only information like component + name and state. + """ + + def __init__(self, hw_component_info, icons, parent=None): + QAbstractTableModel.__init__(self, parent) + self._data = hw_component_info + self._icons = icons + + def rowCount(self, parent): + return len(self._data) + + def columnCount(self, parent): + return 2 + + def headerData(self, col, orientation, role): + if orientation != Qt.Horizontal or role != Qt.DisplayRole: + return None + if col == 0: + return "component" + elif col == 1: + return "state" + + def data(self, index, role): + if not index.isValid(): + return None + + hw_component = self._data[index.row()] + + if role == Qt.DisplayRole: + if index.column() == 0: + return hw_component.name + elif index.column() == 1: + return hw_component.state.label or "not loaded" + + if role == Qt.DecorationRole and index.column() == 0: + return self._icons.get(hw_component.state.label) + + if role == Qt.FontRole and index.column() == 0: + bf = QFont() + bf.setBold(True) + return bf + + if role == Qt.TextAlignmentRole and index.column() == 1: + return Qt.AlignCenter + + class FontDelegate(QStyledItemDelegate): """ Simple delegate for customizing font weight and italization. From cd5573970550a61ad285175917af7876ed10004e Mon Sep 17 00:00:00 2001 From: "mergify[bot]" <37929162+mergify[bot]@users.noreply.github.com> Date: Sun, 13 Oct 2024 13:25:51 +0200 Subject: [PATCH 05/47] Refactor spawner to be able to reuse code for ros2controlcli (backport #1661) (#1695) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * Refactor spawner to be able to reuse code for ros2controlcli (#1661) (cherry picked from commit 0631e3edecadd8b4a50ad2a3dc1374030167f71a) # Conflicts: # controller_manager/controller_manager/spawner.py # controller_manager/test/test_spawner_unspawner.cpp * [Humble] Fix conflicts of 1661 backport (#1735) * Fix conflicts * added controller_type parameter setting to the spawner --------- Co-authored-by: Sai Kishor Kothakota Co-authored-by: Christoph Fröhlich --- .../controller_manager/__init__.py | 8 ++ .../controller_manager_services.py | 104 +++++++++++++++ .../controller_manager/hardware_spawner.py | 14 +- .../controller_manager/spawner.py | 121 +++--------------- .../ros2controlcli/verb/list_controllers.py | 3 +- .../verb/list_hardware_components.py | 3 +- .../verb/list_hardware_interfaces.py | 3 +- 7 files changed, 134 insertions(+), 122 deletions(-) diff --git a/controller_manager/controller_manager/__init__.py b/controller_manager/controller_manager/__init__.py index f49bed4d34..4a8d7daee5 100644 --- a/controller_manager/controller_manager/__init__.py +++ b/controller_manager/controller_manager/__init__.py @@ -23,6 +23,10 @@ set_hardware_component_state, switch_controllers, unload_controller, + get_parameter_from_param_file, + set_controller_parameters, + set_controller_parameters_from_param_file, + bcolors, ) __all__ = [ @@ -36,4 +40,8 @@ "set_hardware_component_state", "switch_controllers", "unload_controller", + "get_parameter_from_param_file", + "set_controller_parameters", + "set_controller_parameters_from_param_file", + "bcolors", ] diff --git a/controller_manager/controller_manager/controller_manager_services.py b/controller_manager/controller_manager/controller_manager_services.py index 00a6f37145..25cd932dab 100644 --- a/controller_manager/controller_manager/controller_manager_services.py +++ b/controller_manager/controller_manager/controller_manager_services.py @@ -26,6 +26,29 @@ ) import rclpy +import yaml +from rcl_interfaces.msg import Parameter + +# @note: The versions conditioning is added here to support the source-compatibility with Humble +# The `get_parameter_value` function is moved to `rclpy.parameter` module from `ros2param.api` module from version 3.6.0 +try: + from rclpy.parameter import get_parameter_value +except ImportError: + from ros2param.api import get_parameter_value +from ros2param.api import call_set_parameters + + +# from https://stackoverflow.com/a/287944 +class bcolors: + MAGENTA = "\033[95m" + OKBLUE = "\033[94m" + OKCYAN = "\033[96m" + OKGREEN = "\033[92m" + WARNING = "\033[93m" + FAIL = "\033[91m" + ENDC = "\033[0m" + BOLD = "\033[1m" + UNDERLINE = "\033[4m" class ServiceNotFoundError(Exception): @@ -219,3 +242,84 @@ def unload_controller(node, controller_manager_name, controller_name, service_ti request, service_timeout, ) + + +def get_parameter_from_param_file(controller_name, namespace, parameter_file, parameter_name): + with open(parameter_file) as f: + namespaced_controller = ( + controller_name if namespace == "/" else f"{namespace}/{controller_name}" + ) + parameters = yaml.safe_load(f) + if namespaced_controller in parameters: + value = parameters[namespaced_controller] + if not isinstance(value, dict) or "ros__parameters" not in value: + raise RuntimeError( + f"YAML file : {parameter_file} is not a valid ROS parameter file for controller : {namespaced_controller}" + ) + if parameter_name in parameters[namespaced_controller]["ros__parameters"]: + return parameters[namespaced_controller]["ros__parameters"][parameter_name] + else: + return None + else: + return None + + +def set_controller_parameters( + node, controller_manager_name, controller_name, parameter_name, parameter_value +): + parameter = Parameter() + parameter.name = controller_name + "." + parameter_name + parameter_string = str(parameter_value) + parameter.value = get_parameter_value(string_value=parameter_string) + + response = call_set_parameters( + node=node, node_name=controller_manager_name, parameters=[parameter] + ) + assert len(response.results) == 1 + result = response.results[0] + if result.successful: + node.get_logger().info( + bcolors.OKCYAN + + 'Setting controller param "' + + parameter_name + + '" to "' + + parameter_string + + '" for ' + + bcolors.BOLD + + controller_name + + bcolors.ENDC + ) + else: + node.get_logger().fatal( + bcolors.FAIL + + 'Could not set controller param "' + + parameter_name + + '" to "' + + parameter_string + + '" for ' + + bcolors.BOLD + + controller_name + + bcolors.ENDC + ) + return False + return True + + +def set_controller_parameters_from_param_file( + node, controller_manager_name, controller_name, parameter_file, namespace=None +): + if parameter_file: + spawner_namespace = namespace if namespace else node.get_namespace() + set_controller_parameters( + node, controller_manager_name, controller_name, "param_file", parameter_file + ) + + controller_type = get_parameter_from_param_file( + controller_name, spawner_namespace, parameter_file, "type" + ) + if controller_type: + if not set_controller_parameters( + node, controller_manager_name, controller_name, "type", controller_type + ): + return False + return True diff --git a/controller_manager/controller_manager/hardware_spawner.py b/controller_manager/controller_manager/hardware_spawner.py index 3e3a487c6a..29c0b5e97c 100644 --- a/controller_manager/controller_manager/hardware_spawner.py +++ b/controller_manager/controller_manager/hardware_spawner.py @@ -19,6 +19,7 @@ from controller_manager import ( list_hardware_components, set_hardware_component_state, + bcolors, ) from controller_manager.controller_manager_services import ServiceNotFoundError @@ -28,19 +29,6 @@ from rclpy.signals import SignalHandlerOptions -# from https://stackoverflow.com/a/287944 -class bcolors: - HEADER = "\033[95m" - OKBLUE = "\033[94m" - OKCYAN = "\033[96m" - OKGREEN = "\033[92m" - WARNING = "\033[93m" - FAIL = "\033[91m" - ENDC = "\033[0m" - BOLD = "\033[1m" - UNDERLINE = "\033[4m" - - def first_match(iterable, predicate): return next((n for n in iterable if predicate(n)), None) diff --git a/controller_manager/controller_manager/spawner.py b/controller_manager/controller_manager/spawner.py index 4b452ef1e0..f20c0a3066 100644 --- a/controller_manager/controller_manager/spawner.py +++ b/controller_manager/controller_manager/spawner.py @@ -19,7 +19,6 @@ import sys import time import warnings -import yaml from controller_manager import ( configure_controller, @@ -27,29 +26,15 @@ load_controller, switch_controllers, unload_controller, + set_controller_parameters, + set_controller_parameters_from_param_file, + bcolors, ) from controller_manager.controller_manager_services import ServiceNotFoundError import rclpy -from rcl_interfaces.msg import Parameter from rclpy.node import Node from rclpy.signals import SignalHandlerOptions -from ros2param.api import call_set_parameters -from ros2param.api import get_parameter_value - -# from https://stackoverflow.com/a/287944 - - -class bcolors: - MAGENTA = "\033[95m" - OKBLUE = "\033[94m" - OKCYAN = "\033[96m" - OKGREEN = "\033[92m" - WARNING = "\033[93m" - FAIL = "\033[91m" - ENDC = "\033[0m" - BOLD = "\033[1m" - UNDERLINE = "\033[4m" def first_match(iterable, predicate): @@ -81,24 +66,6 @@ def is_controller_loaded(node, controller_manager, controller_name, service_time return any(c.name == controller_name for c in controllers) -def get_parameter_from_param_file(controller_name, namespace, parameter_file, parameter_name): - with open(parameter_file) as f: - namespaced_controller = ( - controller_name if namespace == "/" else f"{namespace}/{controller_name}" - ) - parameters = yaml.safe_load(f) - if namespaced_controller in parameters: - value = parameters[namespaced_controller] - if not isinstance(value, dict) or "ros__parameters" not in value: - raise RuntimeError( - f"YAML file : {parameter_file} is not a valid ROS parameter file for controller : {namespaced_controller}" - ) - if parameter_name in parameters[namespaced_controller]["ros__parameters"]: - return parameters[namespaced_controller]["ros__parameters"][parameter_name] - else: - return None - - def main(args=None): rclpy.init(args=args, signal_handler_options=SignalHandlerOptions.NO) @@ -206,75 +173,23 @@ def main(args=None): + bcolors.ENDC ) else: - controller_type = ( - args.controller_type - if param_file is None - else get_parameter_from_param_file( - controller_name, spawner_namespace, param_file, "type" - ) - ) - if controller_type: - parameter = Parameter() - parameter.name = controller_name + ".type" - parameter.value = get_parameter_value(string_value=controller_type) - - response = call_set_parameters( - node=node, node_name=controller_manager_name, parameters=[parameter] - ) - assert len(response.results) == 1 - result = response.results[0] - if result.successful: - node.get_logger().info( - bcolors.OKCYAN - + 'Set controller type to "' - + controller_type - + '" for ' - + bcolors.BOLD - + controller_name - + bcolors.ENDC - ) - else: - node.get_logger().fatal( - bcolors.FAIL - + 'Could not set controller type to "' - + controller_type - + '" for ' - + bcolors.BOLD - + controller_name - + bcolors.ENDC - ) + if args.controller_type: + if not set_controller_parameters( + node, + controller_manager_name, + controller_name, + "type", + args.controller_type, + ): return 1 - if param_file: - parameter = Parameter() - parameter.name = controller_name + ".params_file" - parameter.value = get_parameter_value(string_value=param_file) - - response = call_set_parameters( - node=node, node_name=controller_manager_name, parameters=[parameter] - ) - assert len(response.results) == 1 - result = response.results[0] - if result.successful: - node.get_logger().info( - bcolors.OKCYAN - + 'Set controller params file to "' - + param_file - + '" for ' - + bcolors.BOLD - + controller_name - + bcolors.ENDC - ) - else: - node.get_logger().fatal( - bcolors.FAIL - + 'Could not set controller params file to "' - + param_file - + '" for ' - + bcolors.BOLD - + controller_name - + bcolors.ENDC - ) + if not set_controller_parameters_from_param_file( + node, + controller_manager_name, + controller_name, + param_file, + spawner_namespace, + ): return 1 ret = load_controller(node, controller_manager_name, controller_name) diff --git a/ros2controlcli/ros2controlcli/verb/list_controllers.py b/ros2controlcli/ros2controlcli/verb/list_controllers.py index 8367900cd5..b4ebff94cd 100644 --- a/ros2controlcli/ros2controlcli/verb/list_controllers.py +++ b/ros2controlcli/ros2controlcli/verb/list_controllers.py @@ -12,8 +12,7 @@ # See the License for the specific language governing permissions and # limitations under the License. -from controller_manager import list_controllers -from controller_manager.spawner import bcolors +from controller_manager import list_controllers, bcolors from ros2cli.node.direct import add_arguments from ros2cli.node.strategy import NodeStrategy diff --git a/ros2controlcli/ros2controlcli/verb/list_hardware_components.py b/ros2controlcli/ros2controlcli/verb/list_hardware_components.py index 6c93b65cc4..d614cbc7ea 100644 --- a/ros2controlcli/ros2controlcli/verb/list_hardware_components.py +++ b/ros2controlcli/ros2controlcli/verb/list_hardware_components.py @@ -12,8 +12,7 @@ # See the License for the specific language governing permissions and # limitations under the License. -from controller_manager import list_hardware_components -from controller_manager.spawner import bcolors +from controller_manager import list_hardware_components, bcolors from lifecycle_msgs.msg import State diff --git a/ros2controlcli/ros2controlcli/verb/list_hardware_interfaces.py b/ros2controlcli/ros2controlcli/verb/list_hardware_interfaces.py index 7aa850f3bc..4510998ad9 100644 --- a/ros2controlcli/ros2controlcli/verb/list_hardware_interfaces.py +++ b/ros2controlcli/ros2controlcli/verb/list_hardware_interfaces.py @@ -12,8 +12,7 @@ # See the License for the specific language governing permissions and # limitations under the License. -from controller_manager import list_hardware_interfaces -from controller_manager.spawner import bcolors +from controller_manager import list_hardware_interfaces, bcolors from ros2cli.node.direct import add_arguments from ros2cli.node.strategy import NodeStrategy From 847e655539c93e4e80a1814a69bba9f450382369 Mon Sep 17 00:00:00 2001 From: "mergify[bot]" <37929162+mergify[bot]@users.noreply.github.com> Date: Sun, 13 Oct 2024 13:50:05 +0200 Subject: [PATCH 06/47] Add resources_lock_ lock_guards to avoid race condition when loading robot_description through topic (backport #1451) (#1599) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * Add resources_lock_ lock_guards to avoid race condition when loading robot_description through topic (#1451) (cherry picked from commit 25f2c97eb909c48b96384c7cff7f7f36be8ca509) # Conflicts: # hardware_interface/src/resource_manager.cpp * Try fixing conflict. --------- Co-authored-by: Sai Kishor Kothakota Co-authored-by: Dr. Denis Co-authored-by: Christoph Fröhlich --- hardware_interface/src/resource_manager.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/hardware_interface/src/resource_manager.cpp b/hardware_interface/src/resource_manager.cpp index e585571d35..06c56b4cce 100644 --- a/hardware_interface/src/resource_manager.cpp +++ b/hardware_interface/src/resource_manager.cpp @@ -686,6 +686,7 @@ void ResourceManager::load_urdf( const auto hardware_info = hardware_interface::parse_control_resources_from_urdf(urdf); if (load_and_initialize_components) + std::lock_guard resource_guard(resources_lock_); { for (const auto & individual_hardware_info : hardware_info) { @@ -1209,6 +1210,7 @@ return_type ResourceManager::set_component_state( return false; }; + std::lock_guard guard(resources_lock_); bool found = find_set_component_state( std::bind(&ResourceStorage::set_component_state, resource_storage_.get(), _1, _2), resource_storage_->actuators_); From d3de746d9f0e90d37ebbfe702502138f3cb32ec9 Mon Sep 17 00:00:00 2001 From: "mergify[bot]" <37929162+mergify[bot]@users.noreply.github.com> Date: Sun, 13 Oct 2024 22:19:35 +0200 Subject: [PATCH 07/47] allow extra spawner arguments to not declare every argument in launch utils (#1505) (#1792) (cherry picked from commit fc25478964827d1ae898d60419b2f4dca83a6a45) Co-authored-by: Sai Kishor Kothakota --- controller_manager/controller_manager/launch_utils.py | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/controller_manager/controller_manager/launch_utils.py b/controller_manager/controller_manager/launch_utils.py index e3ef28e928..ead11a1ec8 100644 --- a/controller_manager/controller_manager/launch_utils.py +++ b/controller_manager/controller_manager/launch_utils.py @@ -20,7 +20,7 @@ def generate_load_controller_launch_description( - controller_name, controller_type=None, controller_params_file=None + controller_name, controller_type=None, controller_params_file=None, extra_spawner_args=[] ): """ Generate launch description for loading a controller using spawner. @@ -39,7 +39,8 @@ def generate_load_controller_launch_description( 'joint_state_broadcaster', controller_type='joint_state_broadcaster/JointStateBroadcaster', controller_params_file=os.path.join(get_package_share_directory('my_pkg'), - 'config', 'controller_params.yaml') + 'config', 'controller_params.yaml'), + extra_spawner_args=[--load-only] ) """ @@ -79,6 +80,9 @@ def generate_load_controller_launch_description( ) ] + if extra_spawner_args: + spawner_arguments += extra_spawner_args + spawner = Node( package="controller_manager", executable="spawner", From 3aa31c5f5aa82ca2eabd6c3b8fa8e3a75c1e6ea8 Mon Sep 17 00:00:00 2001 From: "mergify[bot]" <37929162+mergify[bot]@users.noreply.github.com> Date: Mon, 14 Oct 2024 09:13:31 +0200 Subject: [PATCH 08/47] Improve launch utils to support the multiple controller names (#1782) (#1783) Co-authored-by: Sai Kishor Kothakota --- .../controller_manager/launch_utils.py | 38 +++++++++++++------ 1 file changed, 27 insertions(+), 11 deletions(-) diff --git a/controller_manager/controller_manager/launch_utils.py b/controller_manager/controller_manager/launch_utils.py index ead11a1ec8..4cef8743ac 100644 --- a/controller_manager/controller_manager/launch_utils.py +++ b/controller_manager/controller_manager/launch_utils.py @@ -19,8 +19,11 @@ from launch_ros.actions import Node -def generate_load_controller_launch_description( - controller_name, controller_type=None, controller_params_file=None, extra_spawner_args=[] +def generate_controllers_spawner_launch_description( + controller_names: list, + controller_type=None, + controller_params_file=None, + extra_spawner_args=[], ): """ Generate launch description for loading a controller using spawner. @@ -32,11 +35,11 @@ def generate_load_controller_launch_description( Examples -------- # Assuming the controller type and controller parameters are known to the controller_manager - generate_load_controller_launch_description('joint_state_broadcaster') + generate_controllers_spawner_launch_description(['joint_state_broadcaster']) - # Passing controller type and controller parameter file to load - generate_load_controller_launch_description( - 'joint_state_broadcaster', + # Passing controller type and parameter file to load the controller + generate_controllers_spawner_launch_description( + ['joint_state_broadcaster'], controller_type='joint_state_broadcaster/JointStateBroadcaster', controller_params_file=os.path.join(get_package_share_directory('my_pkg'), 'config', 'controller_params.yaml'), @@ -55,11 +58,13 @@ def generate_load_controller_launch_description( description="Wait until the node is interrupted and then unload controller", ) - spawner_arguments = [ - controller_name, - "--controller-manager", - LaunchConfiguration("controller_manager_name"), - ] + spawner_arguments = controller_names + spawner_arguments.extend( + [ + "--controller-manager", + LaunchConfiguration("controller_manager_name"), + ] + ) if controller_type: spawner_arguments += ["--controller-type", controller_type] @@ -98,3 +103,14 @@ def generate_load_controller_launch_description( spawner, ] ) + + +def generate_load_controller_launch_description( + controller_name: str, controller_type=None, controller_params_file=None, extra_spawner_args=[] +): + return generate_controllers_spawner_launch_description( + controller_names=[controller_name], + controller_type=controller_type, + controller_params_file=controller_params_file, + extra_spawner_args=extra_spawner_args, + ) From 7b079631891448edb864384408c10abc74f91345 Mon Sep 17 00:00:00 2001 From: "mergify[bot]" <37929162+mergify[bot]@users.noreply.github.com> Date: Wed, 16 Oct 2024 08:33:17 +0200 Subject: [PATCH 09/47] fix: call configure_controller on 'unconfigured' state instead load_controller (#1794) (#1797) (cherry picked from commit 0ba1428654cbbc69050f8d58eefc39c56b098cb6) Co-authored-by: Santosh Govindaraj <75157452+SantoshGovindaraj@users.noreply.github.com> --- .../rqt_controller_manager/controller_manager.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rqt_controller_manager/rqt_controller_manager/controller_manager.py b/rqt_controller_manager/rqt_controller_manager/controller_manager.py index 3b4a9a7de1..0044649b6f 100644 --- a/rqt_controller_manager/rqt_controller_manager/controller_manager.py +++ b/rqt_controller_manager/rqt_controller_manager/controller_manager.py @@ -261,7 +261,7 @@ def _on_ctrl_menu(self, pos): if action is action_configure: configure_controller(self._node, self._cm_name, ctrl.name) elif action is action_spawn: - load_controller(self._node, self._cm_name, ctrl.name) + configure_controller(self._node, self._cm_name, ctrl.name) self._activate_controller(ctrl.name) else: # Assume controller isn't loaded From 8bf8a6c786856dd28157d5b83205a9026f6fad1d Mon Sep 17 00:00:00 2001 From: "mergify[bot]" <37929162+mergify[bot]@users.noreply.github.com> Date: Fri, 25 Oct 2024 15:39:40 +0200 Subject: [PATCH 10/47] Fix timeout value in std output (backport #1807) (#1812) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * Fix timeout value in std output (#1807) We were using the wrong timeout in the terminal output there. (cherry picked from commit cb91599f8f66aaf39b7485a2f7e131157f633474) # Conflicts: # controller_manager/controller_manager/controller_manager_services.py * Update controller_manager_services.py --------- Co-authored-by: Felix Exner (fexner) Co-authored-by: Christoph Fröhlich --- .../controller_manager/controller_manager_services.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/controller_manager/controller_manager/controller_manager_services.py b/controller_manager/controller_manager/controller_manager_services.py index 25cd932dab..06abece354 100644 --- a/controller_manager/controller_manager/controller_manager_services.py +++ b/controller_manager/controller_manager/controller_manager_services.py @@ -106,7 +106,7 @@ def service_caller( if future.result() is None: node.get_logger().warning( f"Failed getting a result from calling {service_name} in " - f"{service_timeout}. (Attempt {attempt+1} of {max_attempts}.)" + f"{call_timeout}. (Attempt {attempt+1} of {max_attempts}.)" ) else: return future.result() From 24fcfe753b89d8d54d79457e2996916d0d17f5e5 Mon Sep 17 00:00:00 2001 From: "mergify[bot]" <37929162+mergify[bot]@users.noreply.github.com> Date: Sat, 26 Oct 2024 21:21:23 +0100 Subject: [PATCH 11/47] Add -Wconversion flag to protect future developments (#1053) (#1815) --- controller_interface/CMakeLists.txt | 2 +- controller_manager/CMakeLists.txt | 2 +- hardware_interface/CMakeLists.txt | 2 +- hardware_interface/src/component_parser.cpp | 6 ++++-- joint_limits/CMakeLists.txt | 2 +- transmission_interface/CMakeLists.txt | 2 +- 6 files changed, 9 insertions(+), 7 deletions(-) diff --git a/controller_interface/CMakeLists.txt b/controller_interface/CMakeLists.txt index 7486ee3414..62dbad2381 100644 --- a/controller_interface/CMakeLists.txt +++ b/controller_interface/CMakeLists.txt @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.5) project(controller_interface) if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra) + add_compile_options(-Wall -Wextra -Wconversion) endif() find_package(ament_cmake REQUIRED) diff --git a/controller_manager/CMakeLists.txt b/controller_manager/CMakeLists.txt index 53999d4f70..cb4150c17d 100644 --- a/controller_manager/CMakeLists.txt +++ b/controller_manager/CMakeLists.txt @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.5) project(controller_manager) if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra) + add_compile_options(-Wall -Wextra -Wconversion) endif() set(THIS_PACKAGE_INCLUDE_DEPENDS diff --git a/hardware_interface/CMakeLists.txt b/hardware_interface/CMakeLists.txt index 5892f0c3b3..d4091d63c9 100644 --- a/hardware_interface/CMakeLists.txt +++ b/hardware_interface/CMakeLists.txt @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.5) project(hardware_interface) if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra) + add_compile_options(-Wall -Wextra -Wconversion) endif() set(THIS_PACKAGE_INCLUDE_DEPENDS diff --git a/hardware_interface/src/component_parser.cpp b/hardware_interface/src/component_parser.cpp index 7792b0fbf4..e087d39c95 100644 --- a/hardware_interface/src/component_parser.cpp +++ b/hardware_interface/src/component_parser.cpp @@ -348,7 +348,8 @@ ComponentInfo parse_complex_component_from_xml(const tinyxml2::XMLElement * comp component.command_interfaces.push_back(parse_interfaces_from_xml(command_interfaces_it)); component.command_interfaces.back().data_type = parse_data_type_attribute(command_interfaces_it); - component.command_interfaces.back().size = parse_size_attribute(command_interfaces_it); + component.command_interfaces.back().size = + static_cast(parse_size_attribute(command_interfaces_it)); command_interfaces_it = command_interfaces_it->NextSiblingElement(kCommandInterfaceTag); } @@ -358,7 +359,8 @@ ComponentInfo parse_complex_component_from_xml(const tinyxml2::XMLElement * comp { component.state_interfaces.push_back(parse_interfaces_from_xml(state_interfaces_it)); component.state_interfaces.back().data_type = parse_data_type_attribute(state_interfaces_it); - component.state_interfaces.back().size = parse_size_attribute(state_interfaces_it); + component.state_interfaces.back().size = + static_cast(parse_size_attribute(state_interfaces_it)); state_interfaces_it = state_interfaces_it->NextSiblingElement(kStateInterfaceTag); } diff --git a/joint_limits/CMakeLists.txt b/joint_limits/CMakeLists.txt index 314ec67272..52f2044e19 100644 --- a/joint_limits/CMakeLists.txt +++ b/joint_limits/CMakeLists.txt @@ -7,7 +7,7 @@ if(NOT CMAKE_CXX_STANDARD) endif() if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra) + add_compile_options(-Wall -Wextra -Wconversion) endif() find_package(ament_cmake REQUIRED) diff --git a/transmission_interface/CMakeLists.txt b/transmission_interface/CMakeLists.txt index 1a51bbb3e8..a2cf4d7884 100644 --- a/transmission_interface/CMakeLists.txt +++ b/transmission_interface/CMakeLists.txt @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.5) project(transmission_interface) if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra -Wpedantic) + add_compile_options(-Wall -Wextra -Wpedantic -Wconversion) endif() set(THIS_PACKAGE_INCLUDE_DEPENDS From 03bf04ba88b325609af6c6c2a96a2a2db9868004 Mon Sep 17 00:00:00 2001 From: "mergify[bot]" <37929162+mergify[bot]@users.noreply.github.com> Date: Sun, 27 Oct 2024 17:28:30 +0100 Subject: [PATCH 12/47] Add few warning compiler options to error (backport #1181) (#1816) * Add few warning compiler options to error (#1181) * add conversion, unused-but-set-variable, and return-type warnings to error * add shadow variables to error and their fixes for code compilation * apply the same flags to controller interface package * apply the same flags and their fixes to hardware_interface package * apply the same compiler options to the rest of the packages * Deactivate compiler warning for class_loader --------- Co-authored-by: Sai Kishor Kothakota Co-authored-by: Christoph Froehlich --- controller_interface/CMakeLists.txt | 2 +- controller_manager/CMakeLists.txt | 2 +- controller_manager/src/controller_manager.cpp | 48 +++++++++---------- hardware_interface/CMakeLists.txt | 2 +- .../src/mock_components/generic_system.cpp | 8 ++-- .../test/test_resource_manager.cpp | 24 +++++----- joint_limits/CMakeLists.txt | 3 ++ transmission_interface/CMakeLists.txt | 5 +- 8 files changed, 50 insertions(+), 44 deletions(-) diff --git a/controller_interface/CMakeLists.txt b/controller_interface/CMakeLists.txt index 62dbad2381..4d5454430f 100644 --- a/controller_interface/CMakeLists.txt +++ b/controller_interface/CMakeLists.txt @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.5) project(controller_interface) if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra -Wconversion) + add_compile_options(-Wall -Wextra -Werror=conversion -Werror=unused-but-set-variable -Werror=return-type -Werror=shadow) endif() find_package(ament_cmake REQUIRED) diff --git a/controller_manager/CMakeLists.txt b/controller_manager/CMakeLists.txt index cb4150c17d..d8d8fd232a 100644 --- a/controller_manager/CMakeLists.txt +++ b/controller_manager/CMakeLists.txt @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.5) project(controller_manager) if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra -Wconversion) + add_compile_options(-Wall -Wextra -Werror=conversion -Werror=unused-but-set-variable -Werror=return-type -Werror=shadow) endif() set(THIS_PACKAGE_INCLUDE_DEPENDS diff --git a/controller_manager/src/controller_manager.cpp b/controller_manager/src/controller_manager.cpp index 6d8bae1f28..1624b47c2d 100644 --- a/controller_manager/src/controller_manager.cpp +++ b/controller_manager/src/controller_manager.cpp @@ -444,6 +444,8 @@ void ControllerManager::init_resource_manager(const std::string & robot_descript // BEGIN: Keep old functionality on for backwards compatibility std::vector activate_components_on_start = std::vector({}); get_parameter("activate_components_on_start", activate_components_on_start); + rclcpp_lifecycle::State active_state( + State::PRIMARY_STATE_ACTIVE, hardware_interface::lifecycle_state_names::ACTIVE); if (!activate_components_on_start.empty()) { RCLCPP_WARN( @@ -451,8 +453,6 @@ void ControllerManager::init_resource_manager(const std::string & robot_descript "[Deprecated]: Parameter 'activate_components_on_start' is deprecated. " "Components are activated per default. Don't use this parameters in combination with the new " "'hardware_components_initial_state' parameter structure."); - rclcpp_lifecycle::State active_state( - State::PRIMARY_STATE_ACTIVE, hardware_interface::lifecycle_state_names::ACTIVE); for (const auto & component : activate_components_on_start) { resource_manager_->set_component_state(component, active_state); @@ -464,8 +464,6 @@ void ControllerManager::init_resource_manager(const std::string & robot_descript // activate all other components for (const auto & [component, state] : components_to_activate) { - rclcpp_lifecycle::State active_state( - State::PRIMARY_STATE_ACTIVE, hardware_interface::lifecycle_state_names::ACTIVE); if ( resource_manager_->set_component_state(component, active_state) == hardware_interface::return_type::ERROR) @@ -988,7 +986,7 @@ controller_interface::return_type ControllerManager::switch_controller( auto controller_it = std::find_if( controllers.begin(), controllers.end(), std::bind(controller_name_compare, std::placeholders::_1, *ctrl_it)); - controller_interface::return_type ret = controller_interface::return_type::OK; + controller_interface::return_type status = controller_interface::return_type::OK; // if controller is not inactive then do not do any following-controllers checks if (!is_controller_inactive(controller_it->c)) @@ -998,14 +996,14 @@ controller_interface::return_type ControllerManager::switch_controller( "Controller with name '%s' is not inactive so its following " "controllers do not have to be checked, because it cannot be activated.", controller_it->info.name.c_str()); - ret = controller_interface::return_type::ERROR; + status = controller_interface::return_type::ERROR; } else { - ret = check_following_controllers_for_activate(controllers, strictness, controller_it); + status = check_following_controllers_for_activate(controllers, strictness, controller_it); } - if (ret != controller_interface::return_type::OK) + if (status != controller_interface::return_type::OK) { RCLCPP_WARN( get_logger(), @@ -1039,7 +1037,7 @@ controller_interface::return_type ControllerManager::switch_controller( auto controller_it = std::find_if( controllers.begin(), controllers.end(), std::bind(controller_name_compare, std::placeholders::_1, *ctrl_it)); - controller_interface::return_type ret = controller_interface::return_type::OK; + controller_interface::return_type status = controller_interface::return_type::OK; // if controller is not active then skip preceding-controllers checks if (!is_controller_active(controller_it->c)) @@ -1047,14 +1045,14 @@ controller_interface::return_type ControllerManager::switch_controller( RCLCPP_WARN( get_logger(), "Controller with name '%s' can not be deactivated since it is not active.", controller_it->info.name.c_str()); - ret = controller_interface::return_type::ERROR; + status = controller_interface::return_type::ERROR; } else { - ret = check_preceeding_controllers_for_deactivate(controllers, strictness, controller_it); + status = check_preceeding_controllers_for_deactivate(controllers, strictness, controller_it); } - if (ret != controller_interface::return_type::OK) + if (status != controller_interface::return_type::OK) { RCLCPP_WARN( get_logger(), @@ -1135,11 +1133,11 @@ controller_interface::return_type ControllerManager::switch_controller( // check for double stop if (!is_active && in_deactivate_list) { - auto ret = handle_conflict( + auto conflict_status = handle_conflict( "Could not deactivate controller '" + controller.info.name + "' since it is not active"); - if (ret != controller_interface::return_type::OK) + if (conflict_status != controller_interface::return_type::OK) { - return ret; + return conflict_status; } in_deactivate_list = false; deactivate_request_.erase(deactivate_list_it); @@ -1148,11 +1146,11 @@ controller_interface::return_type ControllerManager::switch_controller( // check for doubled activation if (is_active && !in_deactivate_list && in_activate_list) { - auto ret = handle_conflict( + auto conflict_status = handle_conflict( "Could not activate controller '" + controller.info.name + "' since it is already active"); - if (ret != controller_interface::return_type::OK) + if (conflict_status != controller_interface::return_type::OK) { - return ret; + return conflict_status; } in_activate_list = false; activate_request_.erase(activate_list_it); @@ -1161,21 +1159,21 @@ controller_interface::return_type ControllerManager::switch_controller( // check for illegal activation of an unconfigured/finalized controller if (!is_inactive && !in_deactivate_list && in_activate_list) { - auto ret = handle_conflict( + auto conflict_status = handle_conflict( "Could not activate controller '" + controller.info.name + "' since it is not in inactive state"); - if (ret != controller_interface::return_type::OK) + if (conflict_status != controller_interface::return_type::OK) { - return ret; + return conflict_status; } in_activate_list = false; activate_request_.erase(activate_list_it); } const auto extract_interfaces_for_controller = - [this](const ControllerSpec controller, std::vector & request_interface_list) + [this](const ControllerSpec ctrl, std::vector & request_interface_list) { - auto command_interface_config = controller.c->command_interface_configuration(); + auto command_interface_config = ctrl.c->command_interface_configuration(); std::vector command_interface_names = {}; if (command_interface_config.type == controller_interface::interface_configuration_type::ALL) { @@ -1775,8 +1773,8 @@ void ControllerManager::reload_controller_libraries_service_cb( loaded_controllers = get_controller_names(); { // lock controllers - std::lock_guard guard(rt_controllers_wrapper_.controllers_lock_); - for (const auto & controller : rt_controllers_wrapper_.get_updated_list(guard)) + std::lock_guard ctrl_guard(rt_controllers_wrapper_.controllers_lock_); + for (const auto & controller : rt_controllers_wrapper_.get_updated_list(ctrl_guard)) { if (is_controller_active(*controller.c)) { diff --git a/hardware_interface/CMakeLists.txt b/hardware_interface/CMakeLists.txt index d4091d63c9..404fd23101 100644 --- a/hardware_interface/CMakeLists.txt +++ b/hardware_interface/CMakeLists.txt @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.5) project(hardware_interface) if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra -Wconversion) + add_compile_options(-Wall -Wextra -Werror=conversion -Werror=unused-but-set-variable -Werror=return-type -Werror=shadow) endif() set(THIS_PACKAGE_INCLUDE_DEPENDS diff --git a/hardware_interface/src/mock_components/generic_system.cpp b/hardware_interface/src/mock_components/generic_system.cpp index 3d10f16b5a..fb91961d60 100644 --- a/hardware_interface/src/mock_components/generic_system.cpp +++ b/hardware_interface/src/mock_components/generic_system.cpp @@ -594,12 +594,12 @@ return_type GenericSystem::read(const rclcpp::Time & /*time*/, const rclcpp::Dur } else { - for (size_t j = 0; j < joint_states_[POSITION_INTERFACE_INDEX].size(); ++j) + for (size_t k = 0; k < joint_states_[POSITION_INTERFACE_INDEX].size(); ++k) { - if (!std::isnan(joint_commands_[POSITION_INTERFACE_INDEX][j])) + if (!std::isnan(joint_commands_[POSITION_INTERFACE_INDEX][k])) { - joint_states_[POSITION_INTERFACE_INDEX][j] = // apply offset to positions only - joint_commands_[POSITION_INTERFACE_INDEX][j] + + joint_states_[POSITION_INTERFACE_INDEX][k] = // apply offset to positions only + joint_commands_[POSITION_INTERFACE_INDEX][k] + (custom_interface_with_following_offset_.empty() ? position_state_following_offset_ : 0.0); } diff --git a/hardware_interface_testing/test/test_resource_manager.cpp b/hardware_interface_testing/test/test_resource_manager.cpp index 90129f9f64..1157aa74e3 100644 --- a/hardware_interface_testing/test/test_resource_manager.cpp +++ b/hardware_interface_testing/test/test_resource_manager.cpp @@ -232,21 +232,23 @@ TEST_F(ResourceManagerTest, resource_claiming) // Activate components to get all interfaces available activate_components(rm); - const auto command_interface = "joint1/position"; - EXPECT_TRUE(rm.command_interface_is_available(command_interface)); - EXPECT_FALSE(rm.command_interface_is_claimed(command_interface)); - { - auto position_command_interface = rm.claim_command_interface(command_interface); - EXPECT_TRUE(rm.command_interface_is_available(command_interface)); - EXPECT_TRUE(rm.command_interface_is_claimed(command_interface)); + const auto key = "joint1/position"; + EXPECT_TRUE(rm.command_interface_is_available(key)); + EXPECT_FALSE(rm.command_interface_is_claimed(key)); + { - EXPECT_ANY_THROW(rm.claim_command_interface(command_interface)); - EXPECT_TRUE(rm.command_interface_is_available(command_interface)); + auto position_command_interface = rm.claim_command_interface(key); + EXPECT_TRUE(rm.command_interface_is_available(key)); + EXPECT_TRUE(rm.command_interface_is_claimed(key)); + { + EXPECT_ANY_THROW(rm.claim_command_interface(key)); + EXPECT_TRUE(rm.command_interface_is_available(key)); + } } + EXPECT_TRUE(rm.command_interface_is_available(key)); + EXPECT_FALSE(rm.command_interface_is_claimed(key)); } - EXPECT_TRUE(rm.command_interface_is_available(command_interface)); - EXPECT_FALSE(rm.command_interface_is_claimed(command_interface)); // command interfaces can only be claimed once for (const auto & interface_key : diff --git a/joint_limits/CMakeLists.txt b/joint_limits/CMakeLists.txt index 52f2044e19..f67ce32fc1 100644 --- a/joint_limits/CMakeLists.txt +++ b/joint_limits/CMakeLists.txt @@ -5,6 +5,9 @@ project(joint_limits) if(NOT CMAKE_CXX_STANDARD) set(CMAKE_CXX_STANDARD 14) endif() +if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)") + add_compile_options(-Wall -Wextra -Werror=conversion -Werror=unused-but-set-variable -Werror=return-type -Werror=shadow) +endif() if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") add_compile_options(-Wall -Wextra -Wconversion) diff --git a/transmission_interface/CMakeLists.txt b/transmission_interface/CMakeLists.txt index a2cf4d7884..9e8e1e87eb 100644 --- a/transmission_interface/CMakeLists.txt +++ b/transmission_interface/CMakeLists.txt @@ -2,7 +2,10 @@ cmake_minimum_required(VERSION 3.5) project(transmission_interface) if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra -Wpedantic -Wconversion) +add_compile_options(-Wall -Wextra -Werror=conversion -Werror=unused-but-set-variable -Werror=return-type + # deactivating this, because of issue in upstream class_loader_imp.hpp + # -Werror=shadow +) endif() set(THIS_PACKAGE_INCLUDE_DEPENDS From 1d67297e5472ca868bd16f6441ab52bedde66e80 Mon Sep 17 00:00:00 2001 From: "mergify[bot]" <37929162+mergify[bot]@users.noreply.github.com> Date: Sun, 27 Oct 2024 18:22:30 +0100 Subject: [PATCH 13/47] Add custom rosdoc2 config for ros2_control metapackage (#1484) (#1588) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit (cherry picked from commit 86dd7d2734fdfeb5c1289fb015d61c6c2761a615) Co-authored-by: Christoph Fröhlich --- .github/workflows/rosdoc2.yml | 14 + .pre-commit-config.yaml | 1 + doc/Doxyfile | 2579 --------------------------------- ros2_control/doc/conf.py | 5 + ros2_control/doc/index.rst | 32 + ros2_control/package.xml | 3 + ros2_control/rosdoc2.yaml | 20 + 7 files changed, 75 insertions(+), 2579 deletions(-) create mode 100644 .github/workflows/rosdoc2.yml delete mode 100644 doc/Doxyfile create mode 100644 ros2_control/doc/conf.py create mode 100644 ros2_control/doc/index.rst create mode 100644 ros2_control/rosdoc2.yaml diff --git a/.github/workflows/rosdoc2.yml b/.github/workflows/rosdoc2.yml new file mode 100644 index 0000000000..07a9e2904a --- /dev/null +++ b/.github/workflows/rosdoc2.yml @@ -0,0 +1,14 @@ +name: rosdoc2 + +on: + workflow_dispatch: + pull_request: + paths: + - ros2_control/doc/** + - ros2_control/rosdoc2.yaml + - ros2_control/package.xml + + +jobs: + check: + uses: ros-controls/ros2_control_ci/.github/workflows/reusable-rosdoc2.yml@master diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index b3b9424576..63e7f08682 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -26,6 +26,7 @@ repos: - id: check-symlinks - id: check-xml - id: check-yaml + args: ["--allow-multiple-documents"] - id: debug-statements - id: end-of-file-fixer - id: mixed-line-ending diff --git a/doc/Doxyfile b/doc/Doxyfile deleted file mode 100644 index d05c75a0b6..0000000000 --- a/doc/Doxyfile +++ /dev/null @@ -1,2579 +0,0 @@ -# Doxyfile 1.8.17 - -# This file describes the settings to be used by the documentation system -# doxygen (www.doxygen.org) for a project. -# -# All text after a double hash (##) is considered a comment and is placed in -# front of the TAG it is preceding. -# -# All text after a single hash (#) is considered a comment and will be ignored. -# The format is: -# TAG = value [value, ...] -# For lists, items can also be appended using: -# TAG += value [value, ...] -# Values that contain spaces should be placed between quotes (\" \"). - -#--------------------------------------------------------------------------- -# Project related configuration options -#--------------------------------------------------------------------------- - -# This tag specifies the encoding used for all characters in the configuration -# file that follow. The default is UTF-8 which is also the encoding used for all -# text before the first occurrence of this tag. Doxygen uses libiconv (or the -# iconv built into libc) for the transcoding. See -# https://www.gnu.org/software/libiconv/ for the list of possible encodings. -# The default value is: UTF-8. - -DOXYFILE_ENCODING = UTF-8 - -# The PROJECT_NAME tag is a single word (or a sequence of words surrounded by -# double-quotes, unless you are using Doxywizard) that should identify the -# project for which the documentation is generated. This name is used in the -# title of most generated pages and in a few other places. -# The default value is: My Project. - -PROJECT_NAME = "ROS2 Control" - -# The PROJECT_NUMBER tag can be used to enter a project or revision number. This -# could be handy for archiving the generated documentation or if some version -# control system is used. - -PROJECT_NUMBER = - -# Using the PROJECT_BRIEF tag one can provide an optional one line description -# for a project that appears at the top of each page and should give viewer a -# quick idea about the purpose of the project. Keep the description short. - -PROJECT_BRIEF = - -# With the PROJECT_LOGO tag one can specify a logo or an icon that is included -# in the documentation. The maximum height of the logo should not exceed 55 -# pixels and the maximum width should not exceed 200 pixels. Doxygen will copy -# the logo to the output directory. - -PROJECT_LOGO = - -# The OUTPUT_DIRECTORY tag is used to specify the (relative or absolute) path -# into which the generated documentation will be written. If a relative path is -# entered, it will be relative to the location where doxygen was started. If -# left blank the current directory will be used. - -OUTPUT_DIRECTORY = doc/_build/ - -# If the CREATE_SUBDIRS tag is set to YES then doxygen will create 4096 sub- -# directories (in 2 levels) under the output directory of each output format and -# will distribute the generated files over these directories. Enabling this -# option can be useful when feeding doxygen a huge amount of source files, where -# putting all generated files in the same directory would otherwise causes -# performance problems for the file system. -# The default value is: NO. - -CREATE_SUBDIRS = NO - -# If the ALLOW_UNICODE_NAMES tag is set to YES, doxygen will allow non-ASCII -# characters to appear in the names of generated files. If set to NO, non-ASCII -# characters will be escaped, for example _xE3_x81_x84 will be used for Unicode -# U+3044. -# The default value is: NO. - -ALLOW_UNICODE_NAMES = NO - -# The OUTPUT_LANGUAGE tag is used to specify the language in which all -# documentation generated by doxygen is written. Doxygen will use this -# information to generate all constant output in the proper language. -# Possible values are: Afrikaans, Arabic, Armenian, Brazilian, Catalan, Chinese, -# Chinese-Traditional, Croatian, Czech, Danish, Dutch, English (United States), -# Esperanto, Farsi (Persian), Finnish, French, German, Greek, Hungarian, -# Indonesian, Italian, Japanese, Japanese-en (Japanese with English messages), -# Korean, Korean-en (Korean with English messages), Latvian, Lithuanian, -# Macedonian, Norwegian, Persian (Farsi), Polish, Portuguese, Romanian, Russian, -# Serbian, Serbian-Cyrillic, Slovak, Slovene, Spanish, Swedish, Turkish, -# Ukrainian and Vietnamese. -# The default value is: English. - -OUTPUT_LANGUAGE = English - -# The OUTPUT_TEXT_DIRECTION tag is used to specify the direction in which all -# documentation generated by doxygen is written. Doxygen will use this -# information to generate all generated output in the proper direction. -# Possible values are: None, LTR, RTL and Context. -# The default value is: None. - -OUTPUT_TEXT_DIRECTION = None - -# If the BRIEF_MEMBER_DESC tag is set to YES, doxygen will include brief member -# descriptions after the members that are listed in the file and class -# documentation (similar to Javadoc). Set to NO to disable this. -# The default value is: YES. - -BRIEF_MEMBER_DESC = YES - -# If the REPEAT_BRIEF tag is set to YES, doxygen will prepend the brief -# description of a member or function before the detailed description -# -# Note: If both HIDE_UNDOC_MEMBERS and BRIEF_MEMBER_DESC are set to NO, the -# brief descriptions will be completely suppressed. -# The default value is: YES. - -REPEAT_BRIEF = YES - -# This tag implements a quasi-intelligent brief description abbreviator that is -# used to form the text in various listings. Each string in this list, if found -# as the leading text of the brief description, will be stripped from the text -# and the result, after processing the whole list, is used as the annotated -# text. Otherwise, the brief description is used as-is. If left blank, the -# following values are used ($name is automatically replaced with the name of -# the entity):The $name class, The $name widget, The $name file, is, provides, -# specifies, contains, represents, a, an and the. - -ABBREVIATE_BRIEF = "The $name class" \ - "The $name widget" \ - "The $name file" \ - is \ - provides \ - specifies \ - contains \ - represents \ - a \ - an \ - the - -# If the ALWAYS_DETAILED_SEC and REPEAT_BRIEF tags are both set to YES then -# doxygen will generate a detailed section even if there is only a brief -# description. -# The default value is: NO. - -ALWAYS_DETAILED_SEC = NO - -# If the INLINE_INHERITED_MEMB tag is set to YES, doxygen will show all -# inherited members of a class in the documentation of that class as if those -# members were ordinary class members. Constructors, destructors and assignment -# operators of the base classes will not be shown. -# The default value is: NO. - -INLINE_INHERITED_MEMB = NO - -# If the FULL_PATH_NAMES tag is set to YES, doxygen will prepend the full path -# before files name in the file list and in the header files. If set to NO the -# shortest path that makes the file name unique will be used -# The default value is: YES. - -FULL_PATH_NAMES = YES - -# The STRIP_FROM_PATH tag can be used to strip a user-defined part of the path. -# Stripping is only done if one of the specified strings matches the left-hand -# part of the path. The tag can be used to show relative paths in the file list. -# If left blank the directory from which doxygen is run is used as the path to -# strip. -# -# Note that you can specify absolute paths here, but also relative paths, which -# will be relative from the directory where doxygen is started. -# This tag requires that the tag FULL_PATH_NAMES is set to YES. - -STRIP_FROM_PATH = - -# The STRIP_FROM_INC_PATH tag can be used to strip a user-defined part of the -# path mentioned in the documentation of a class, which tells the reader which -# header file to include in order to use a class. If left blank only the name of -# the header file containing the class definition is used. Otherwise one should -# specify the list of include paths that are normally passed to the compiler -# using the -I flag. - -STRIP_FROM_INC_PATH = - -# If the SHORT_NAMES tag is set to YES, doxygen will generate much shorter (but -# less readable) file names. This can be useful is your file systems doesn't -# support long names like on DOS, Mac, or CD-ROM. -# The default value is: NO. - -SHORT_NAMES = NO - -# If the JAVADOC_AUTOBRIEF tag is set to YES then doxygen will interpret the -# first line (until the first dot) of a Javadoc-style comment as the brief -# description. If set to NO, the Javadoc-style will behave just like regular Qt- -# style comments (thus requiring an explicit @brief command for a brief -# description.) -# The default value is: NO. - -JAVADOC_AUTOBRIEF = NO - -# If the JAVADOC_BANNER tag is set to YES then doxygen will interpret a line -# such as -# /*************** -# as being the beginning of a Javadoc-style comment "banner". If set to NO, the -# Javadoc-style will behave just like regular comments and it will not be -# interpreted by doxygen. -# The default value is: NO. - -JAVADOC_BANNER = NO - -# If the QT_AUTOBRIEF tag is set to YES then doxygen will interpret the first -# line (until the first dot) of a Qt-style comment as the brief description. If -# set to NO, the Qt-style will behave just like regular Qt-style comments (thus -# requiring an explicit \brief command for a brief description.) -# The default value is: NO. - -QT_AUTOBRIEF = NO - -# The MULTILINE_CPP_IS_BRIEF tag can be set to YES to make doxygen treat a -# multi-line C++ special comment block (i.e. a block of //! or /// comments) as -# a brief description. This used to be the default behavior. The new default is -# to treat a multi-line C++ comment block as a detailed description. Set this -# tag to YES if you prefer the old behavior instead. -# -# Note that setting this tag to YES also means that rational rose comments are -# not recognized any more. -# The default value is: NO. - -MULTILINE_CPP_IS_BRIEF = NO - -# If the INHERIT_DOCS tag is set to YES then an undocumented member inherits the -# documentation from any documented member that it re-implements. -# The default value is: YES. - -INHERIT_DOCS = YES - -# If the SEPARATE_MEMBER_PAGES tag is set to YES then doxygen will produce a new -# page for each member. If set to NO, the documentation of a member will be part -# of the file/class/namespace that contains it. -# The default value is: NO. - -SEPARATE_MEMBER_PAGES = NO - -# The TAB_SIZE tag can be used to set the number of spaces in a tab. Doxygen -# uses this value to replace tabs by spaces in code fragments. -# Minimum value: 1, maximum value: 16, default value: 4. - -TAB_SIZE = 4 - -# This tag can be used to specify a number of aliases that act as commands in -# the documentation. An alias has the form: -# name=value -# For example adding -# "sideeffect=@par Side Effects:\n" -# will allow you to put the command \sideeffect (or @sideeffect) in the -# documentation, which will result in a user-defined paragraph with heading -# "Side Effects:". You can put \n's in the value part of an alias to insert -# newlines (in the resulting output). You can put ^^ in the value part of an -# alias to insert a newline as if a physical newline was in the original file. -# When you need a literal { or } or , in the value part of an alias you have to -# escape them by means of a backslash (\), this can lead to conflicts with the -# commands \{ and \} for these it is advised to use the version @{ and @} or use -# a double escape (\\{ and \\}) - -ALIASES = - -# This tag can be used to specify a number of word-keyword mappings (TCL only). -# A mapping has the form "name=value". For example adding "class=itcl::class" -# will allow you to use the command class in the itcl::class meaning. - -TCL_SUBST = - -# Set the OPTIMIZE_OUTPUT_FOR_C tag to YES if your project consists of C sources -# only. Doxygen will then generate output that is more tailored for C. For -# instance, some of the names that are used will be different. The list of all -# members will be omitted, etc. -# The default value is: NO. - -OPTIMIZE_OUTPUT_FOR_C = NO - -# Set the OPTIMIZE_OUTPUT_JAVA tag to YES if your project consists of Java or -# Python sources only. Doxygen will then generate output that is more tailored -# for that language. For instance, namespaces will be presented as packages, -# qualified scopes will look different, etc. -# The default value is: NO. - -OPTIMIZE_OUTPUT_JAVA = NO - -# Set the OPTIMIZE_FOR_FORTRAN tag to YES if your project consists of Fortran -# sources. Doxygen will then generate output that is tailored for Fortran. -# The default value is: NO. - -OPTIMIZE_FOR_FORTRAN = NO - -# Set the OPTIMIZE_OUTPUT_VHDL tag to YES if your project consists of VHDL -# sources. Doxygen will then generate output that is tailored for VHDL. -# The default value is: NO. - -OPTIMIZE_OUTPUT_VHDL = NO - -# Set the OPTIMIZE_OUTPUT_SLICE tag to YES if your project consists of Slice -# sources only. Doxygen will then generate output that is more tailored for that -# language. For instance, namespaces will be presented as modules, types will be -# separated into more groups, etc. -# The default value is: NO. - -OPTIMIZE_OUTPUT_SLICE = NO - -# Doxygen selects the parser to use depending on the extension of the files it -# parses. With this tag you can assign which parser to use for a given -# extension. Doxygen has a built-in mapping, but you can override or extend it -# using this tag. The format is ext=language, where ext is a file extension, and -# language is one of the parsers supported by doxygen: IDL, Java, JavaScript, -# Csharp (C#), C, C++, D, PHP, md (Markdown), Objective-C, Python, Slice, -# Fortran (fixed format Fortran: FortranFixed, free formatted Fortran: -# FortranFree, unknown formatted Fortran: Fortran. In the later case the parser -# tries to guess whether the code is fixed or free formatted code, this is the -# default for Fortran type files), VHDL, tcl. For instance to make doxygen treat -# .inc files as Fortran files (default is PHP), and .f files as C (default is -# Fortran), use: inc=Fortran f=C. -# -# Note: For files without extension you can use no_extension as a placeholder. -# -# Note that for custom extensions you also need to set FILE_PATTERNS otherwise -# the files are not read by doxygen. - -EXTENSION_MAPPING = - -# If the MARKDOWN_SUPPORT tag is enabled then doxygen pre-processes all comments -# according to the Markdown format, which allows for more readable -# documentation. See https://daringfireball.net/projects/markdown/ for details. -# The output of markdown processing is further processed by doxygen, so you can -# mix doxygen, HTML, and XML commands with Markdown formatting. Disable only in -# case of backward compatibilities issues. -# The default value is: YES. - -MARKDOWN_SUPPORT = YES - -# When the TOC_INCLUDE_HEADINGS tag is set to a non-zero value, all headings up -# to that level are automatically included in the table of contents, even if -# they do not have an id attribute. -# Note: This feature currently applies only to Markdown headings. -# Minimum value: 0, maximum value: 99, default value: 5. -# This tag requires that the tag MARKDOWN_SUPPORT is set to YES. - -TOC_INCLUDE_HEADINGS = 5 - -# When enabled doxygen tries to link words that correspond to documented -# classes, or namespaces to their corresponding documentation. Such a link can -# be prevented in individual cases by putting a % sign in front of the word or -# globally by setting AUTOLINK_SUPPORT to NO. -# The default value is: YES. - -AUTOLINK_SUPPORT = YES - -# If you use STL classes (i.e. std::string, std::vector, etc.) but do not want -# to include (a tag file for) the STL sources as input, then you should set this -# tag to YES in order to let doxygen match functions declarations and -# definitions whose arguments contain STL classes (e.g. func(std::string); -# versus func(std::string) {}). This also make the inheritance and collaboration -# diagrams that involve STL classes more complete and accurate. -# The default value is: NO. - -BUILTIN_STL_SUPPORT = NO - -# If you use Microsoft's C++/CLI language, you should set this option to YES to -# enable parsing support. -# The default value is: NO. - -CPP_CLI_SUPPORT = NO - -# Set the SIP_SUPPORT tag to YES if your project consists of sip (see: -# https://www.riverbankcomputing.com/software/sip/intro) sources only. Doxygen -# will parse them like normal C++ but will assume all classes use public instead -# of private inheritance when no explicit protection keyword is present. -# The default value is: NO. - -SIP_SUPPORT = NO - -# For Microsoft's IDL there are propget and propput attributes to indicate -# getter and setter methods for a property. Setting this option to YES will make -# doxygen to replace the get and set methods by a property in the documentation. -# This will only work if the methods are indeed getting or setting a simple -# type. If this is not the case, or you want to show the methods anyway, you -# should set this option to NO. -# The default value is: YES. - -IDL_PROPERTY_SUPPORT = YES - -# If member grouping is used in the documentation and the DISTRIBUTE_GROUP_DOC -# tag is set to YES then doxygen will reuse the documentation of the first -# member in the group (if any) for the other members of the group. By default -# all members of a group must be documented explicitly. -# The default value is: NO. - -DISTRIBUTE_GROUP_DOC = NO - -# If one adds a struct or class to a group and this option is enabled, then also -# any nested class or struct is added to the same group. By default this option -# is disabled and one has to add nested compounds explicitly via \ingroup. -# The default value is: NO. - -GROUP_NESTED_COMPOUNDS = NO - -# Set the SUBGROUPING tag to YES to allow class member groups of the same type -# (for instance a group of public functions) to be put as a subgroup of that -# type (e.g. under the Public Functions section). Set it to NO to prevent -# subgrouping. Alternatively, this can be done per class using the -# \nosubgrouping command. -# The default value is: YES. - -SUBGROUPING = YES - -# When the INLINE_GROUPED_CLASSES tag is set to YES, classes, structs and unions -# are shown inside the group in which they are included (e.g. using \ingroup) -# instead of on a separate page (for HTML and Man pages) or section (for LaTeX -# and RTF). -# -# Note that this feature does not work in combination with -# SEPARATE_MEMBER_PAGES. -# The default value is: NO. - -INLINE_GROUPED_CLASSES = NO - -# When the INLINE_SIMPLE_STRUCTS tag is set to YES, structs, classes, and unions -# with only public data fields or simple typedef fields will be shown inline in -# the documentation of the scope in which they are defined (i.e. file, -# namespace, or group documentation), provided this scope is documented. If set -# to NO, structs, classes, and unions are shown on a separate page (for HTML and -# Man pages) or section (for LaTeX and RTF). -# The default value is: NO. - -INLINE_SIMPLE_STRUCTS = NO - -# When TYPEDEF_HIDES_STRUCT tag is enabled, a typedef of a struct, union, or -# enum is documented as struct, union, or enum with the name of the typedef. So -# typedef struct TypeS {} TypeT, will appear in the documentation as a struct -# with name TypeT. When disabled the typedef will appear as a member of a file, -# namespace, or class. And the struct will be named TypeS. This can typically be -# useful for C code in case the coding convention dictates that all compound -# types are typedef'ed and only the typedef is referenced, never the tag name. -# The default value is: NO. - -TYPEDEF_HIDES_STRUCT = NO - -# The size of the symbol lookup cache can be set using LOOKUP_CACHE_SIZE. This -# cache is used to resolve symbols given their name and scope. Since this can be -# an expensive process and often the same symbol appears multiple times in the -# code, doxygen keeps a cache of pre-resolved symbols. If the cache is too small -# doxygen will become slower. If the cache is too large, memory is wasted. The -# cache size is given by this formula: 2^(16+LOOKUP_CACHE_SIZE). The valid range -# is 0..9, the default is 0, corresponding to a cache size of 2^16=65536 -# symbols. At the end of a run doxygen will report the cache usage and suggest -# the optimal cache size from a speed point of view. -# Minimum value: 0, maximum value: 9, default value: 0. - -LOOKUP_CACHE_SIZE = 0 - -#--------------------------------------------------------------------------- -# Build related configuration options -#--------------------------------------------------------------------------- - -# If the EXTRACT_ALL tag is set to YES, doxygen will assume all entities in -# documentation are documented, even if no documentation was available. Private -# class members and static file members will be hidden unless the -# EXTRACT_PRIVATE respectively EXTRACT_STATIC tags are set to YES. -# Note: This will also disable the warnings about undocumented members that are -# normally produced when WARNINGS is set to YES. -# The default value is: NO. - -EXTRACT_ALL = NO - -# If the EXTRACT_PRIVATE tag is set to YES, all private members of a class will -# be included in the documentation. -# The default value is: NO. - -EXTRACT_PRIVATE = NO - -# If the EXTRACT_PRIV_VIRTUAL tag is set to YES, documented private virtual -# methods of a class will be included in the documentation. -# The default value is: NO. - -EXTRACT_PRIV_VIRTUAL = NO - -# If the EXTRACT_PACKAGE tag is set to YES, all members with package or internal -# scope will be included in the documentation. -# The default value is: NO. - -EXTRACT_PACKAGE = NO - -# If the EXTRACT_STATIC tag is set to YES, all static members of a file will be -# included in the documentation. -# The default value is: NO. - -EXTRACT_STATIC = NO - -# If the EXTRACT_LOCAL_CLASSES tag is set to YES, classes (and structs) defined -# locally in source files will be included in the documentation. If set to NO, -# only classes defined in header files are included. Does not have any effect -# for Java sources. -# The default value is: YES. - -EXTRACT_LOCAL_CLASSES = YES - -# This flag is only useful for Objective-C code. If set to YES, local methods, -# which are defined in the implementation section but not in the interface are -# included in the documentation. If set to NO, only methods in the interface are -# included. -# The default value is: NO. - -EXTRACT_LOCAL_METHODS = NO - -# If this flag is set to YES, the members of anonymous namespaces will be -# extracted and appear in the documentation as a namespace called -# 'anonymous_namespace{file}', where file will be replaced with the base name of -# the file that contains the anonymous namespace. By default anonymous namespace -# are hidden. -# The default value is: NO. - -EXTRACT_ANON_NSPACES = NO - -# If the HIDE_UNDOC_MEMBERS tag is set to YES, doxygen will hide all -# undocumented members inside documented classes or files. If set to NO these -# members will be included in the various overviews, but no documentation -# section is generated. This option has no effect if EXTRACT_ALL is enabled. -# The default value is: NO. - -HIDE_UNDOC_MEMBERS = NO - -# If the HIDE_UNDOC_CLASSES tag is set to YES, doxygen will hide all -# undocumented classes that are normally visible in the class hierarchy. If set -# to NO, these classes will be included in the various overviews. This option -# has no effect if EXTRACT_ALL is enabled. -# The default value is: NO. - -HIDE_UNDOC_CLASSES = NO - -# If the HIDE_FRIEND_COMPOUNDS tag is set to YES, doxygen will hide all friend -# declarations. If set to NO, these declarations will be included in the -# documentation. -# The default value is: NO. - -HIDE_FRIEND_COMPOUNDS = NO - -# If the HIDE_IN_BODY_DOCS tag is set to YES, doxygen will hide any -# documentation blocks found inside the body of a function. If set to NO, these -# blocks will be appended to the function's detailed documentation block. -# The default value is: NO. - -HIDE_IN_BODY_DOCS = NO - -# The INTERNAL_DOCS tag determines if documentation that is typed after a -# \internal command is included. If the tag is set to NO then the documentation -# will be excluded. Set it to YES to include the internal documentation. -# The default value is: NO. - -INTERNAL_DOCS = NO - -# If the CASE_SENSE_NAMES tag is set to NO then doxygen will only generate file -# names in lower-case letters. If set to YES, upper-case letters are also -# allowed. This is useful if you have classes or files whose names only differ -# in case and if your file system supports case sensitive file names. Windows -# (including Cygwin) ands Mac users are advised to set this option to NO. -# The default value is: system dependent. - -CASE_SENSE_NAMES = YES - -# If the HIDE_SCOPE_NAMES tag is set to NO then doxygen will show members with -# their full class and namespace scopes in the documentation. If set to YES, the -# scope will be hidden. -# The default value is: NO. - -HIDE_SCOPE_NAMES = NO - -# If the HIDE_COMPOUND_REFERENCE tag is set to NO (default) then doxygen will -# append additional text to a page's title, such as Class Reference. If set to -# YES the compound reference will be hidden. -# The default value is: NO. - -HIDE_COMPOUND_REFERENCE= NO - -# If the SHOW_INCLUDE_FILES tag is set to YES then doxygen will put a list of -# the files that are included by a file in the documentation of that file. -# The default value is: YES. - -SHOW_INCLUDE_FILES = YES - -# If the SHOW_GROUPED_MEMB_INC tag is set to YES then Doxygen will add for each -# grouped member an include statement to the documentation, telling the reader -# which file to include in order to use the member. -# The default value is: NO. - -SHOW_GROUPED_MEMB_INC = NO - -# If the FORCE_LOCAL_INCLUDES tag is set to YES then doxygen will list include -# files with double quotes in the documentation rather than with sharp brackets. -# The default value is: NO. - -FORCE_LOCAL_INCLUDES = NO - -# If the INLINE_INFO tag is set to YES then a tag [inline] is inserted in the -# documentation for inline members. -# The default value is: YES. - -INLINE_INFO = YES - -# If the SORT_MEMBER_DOCS tag is set to YES then doxygen will sort the -# (detailed) documentation of file and class members alphabetically by member -# name. If set to NO, the members will appear in declaration order. -# The default value is: YES. - -SORT_MEMBER_DOCS = YES - -# If the SORT_BRIEF_DOCS tag is set to YES then doxygen will sort the brief -# descriptions of file, namespace and class members alphabetically by member -# name. If set to NO, the members will appear in declaration order. Note that -# this will also influence the order of the classes in the class list. -# The default value is: NO. - -SORT_BRIEF_DOCS = NO - -# If the SORT_MEMBERS_CTORS_1ST tag is set to YES then doxygen will sort the -# (brief and detailed) documentation of class members so that constructors and -# destructors are listed first. If set to NO the constructors will appear in the -# respective orders defined by SORT_BRIEF_DOCS and SORT_MEMBER_DOCS. -# Note: If SORT_BRIEF_DOCS is set to NO this option is ignored for sorting brief -# member documentation. -# Note: If SORT_MEMBER_DOCS is set to NO this option is ignored for sorting -# detailed member documentation. -# The default value is: NO. - -SORT_MEMBERS_CTORS_1ST = NO - -# If the SORT_GROUP_NAMES tag is set to YES then doxygen will sort the hierarchy -# of group names into alphabetical order. If set to NO the group names will -# appear in their defined order. -# The default value is: NO. - -SORT_GROUP_NAMES = NO - -# If the SORT_BY_SCOPE_NAME tag is set to YES, the class list will be sorted by -# fully-qualified names, including namespaces. If set to NO, the class list will -# be sorted only by class name, not including the namespace part. -# Note: This option is not very useful if HIDE_SCOPE_NAMES is set to YES. -# Note: This option applies only to the class list, not to the alphabetical -# list. -# The default value is: NO. - -SORT_BY_SCOPE_NAME = NO - -# If the STRICT_PROTO_MATCHING option is enabled and doxygen fails to do proper -# type resolution of all parameters of a function it will reject a match between -# the prototype and the implementation of a member function even if there is -# only one candidate or it is obvious which candidate to choose by doing a -# simple string match. By disabling STRICT_PROTO_MATCHING doxygen will still -# accept a match between prototype and implementation in such cases. -# The default value is: NO. - -STRICT_PROTO_MATCHING = NO - -# The GENERATE_TODOLIST tag can be used to enable (YES) or disable (NO) the todo -# list. This list is created by putting \todo commands in the documentation. -# The default value is: YES. - -GENERATE_TODOLIST = YES - -# The GENERATE_TESTLIST tag can be used to enable (YES) or disable (NO) the test -# list. This list is created by putting \test commands in the documentation. -# The default value is: YES. - -GENERATE_TESTLIST = YES - -# The GENERATE_BUGLIST tag can be used to enable (YES) or disable (NO) the bug -# list. This list is created by putting \bug commands in the documentation. -# The default value is: YES. - -GENERATE_BUGLIST = YES - -# The GENERATE_DEPRECATEDLIST tag can be used to enable (YES) or disable (NO) -# the deprecated list. This list is created by putting \deprecated commands in -# the documentation. -# The default value is: YES. - -GENERATE_DEPRECATEDLIST= YES - -# The ENABLED_SECTIONS tag can be used to enable conditional documentation -# sections, marked by \if ... \endif and \cond -# ... \endcond blocks. - -ENABLED_SECTIONS = - -# The MAX_INITIALIZER_LINES tag determines the maximum number of lines that the -# initial value of a variable or macro / define can have for it to appear in the -# documentation. If the initializer consists of more lines than specified here -# it will be hidden. Use a value of 0 to hide initializers completely. The -# appearance of the value of individual variables and macros / defines can be -# controlled using \showinitializer or \hideinitializer command in the -# documentation regardless of this setting. -# Minimum value: 0, maximum value: 10000, default value: 30. - -MAX_INITIALIZER_LINES = 30 - -# Set the SHOW_USED_FILES tag to NO to disable the list of files generated at -# the bottom of the documentation of classes and structs. If set to YES, the -# list will mention the files that were used to generate the documentation. -# The default value is: YES. - -SHOW_USED_FILES = YES - -# Set the SHOW_FILES tag to NO to disable the generation of the Files page. This -# will remove the Files entry from the Quick Index and from the Folder Tree View -# (if specified). -# The default value is: YES. - -SHOW_FILES = YES - -# Set the SHOW_NAMESPACES tag to NO to disable the generation of the Namespaces -# page. This will remove the Namespaces entry from the Quick Index and from the -# Folder Tree View (if specified). -# The default value is: YES. - -SHOW_NAMESPACES = YES - -# The FILE_VERSION_FILTER tag can be used to specify a program or script that -# doxygen should invoke to get the current version for each file (typically from -# the version control system). Doxygen will invoke the program by executing (via -# popen()) the command command input-file, where command is the value of the -# FILE_VERSION_FILTER tag, and input-file is the name of an input file provided -# by doxygen. Whatever the program writes to standard output is used as the file -# version. For an example see the documentation. - -FILE_VERSION_FILTER = - -# The LAYOUT_FILE tag can be used to specify a layout file which will be parsed -# by doxygen. The layout file controls the global structure of the generated -# output files in an output format independent way. To create the layout file -# that represents doxygen's defaults, run doxygen with the -l option. You can -# optionally specify a file name after the option, if omitted DoxygenLayout.xml -# will be used as the name of the layout file. -# -# Note that if you run doxygen from a directory containing a file called -# DoxygenLayout.xml, doxygen will parse it automatically even if the LAYOUT_FILE -# tag is left empty. - -LAYOUT_FILE = - -# The CITE_BIB_FILES tag can be used to specify one or more bib files containing -# the reference definitions. This must be a list of .bib files. The .bib -# extension is automatically appended if omitted. This requires the bibtex tool -# to be installed. See also https://en.wikipedia.org/wiki/BibTeX for more info. -# For LaTeX the style of the bibliography can be controlled using -# LATEX_BIB_STYLE. To use this feature you need bibtex and perl available in the -# search path. See also \cite for info how to create references. - -CITE_BIB_FILES = - -#--------------------------------------------------------------------------- -# Configuration options related to warning and progress messages -#--------------------------------------------------------------------------- - -# The QUIET tag can be used to turn on/off the messages that are generated to -# standard output by doxygen. If QUIET is set to YES this implies that the -# messages are off. -# The default value is: NO. - -QUIET = NO - -# The WARNINGS tag can be used to turn on/off the warning messages that are -# generated to standard error (stderr) by doxygen. If WARNINGS is set to YES -# this implies that the warnings are on. -# -# Tip: Turn warnings on while writing the documentation. -# The default value is: YES. - -WARNINGS = YES - -# If the WARN_IF_UNDOCUMENTED tag is set to YES then doxygen will generate -# warnings for undocumented members. If EXTRACT_ALL is set to YES then this flag -# will automatically be disabled. -# The default value is: YES. - -WARN_IF_UNDOCUMENTED = YES - -# If the WARN_IF_DOC_ERROR tag is set to YES, doxygen will generate warnings for -# potential errors in the documentation, such as not documenting some parameters -# in a documented function, or documenting parameters that don't exist or using -# markup commands wrongly. -# The default value is: YES. - -WARN_IF_DOC_ERROR = YES - -# This WARN_NO_PARAMDOC option can be enabled to get warnings for functions that -# are documented, but have no documentation for their parameters or return -# value. If set to NO, doxygen will only warn about wrong or incomplete -# parameter documentation, but not about the absence of documentation. If -# EXTRACT_ALL is set to YES then this flag will automatically be disabled. -# The default value is: NO. - -WARN_NO_PARAMDOC = NO - -# If the WARN_AS_ERROR tag is set to YES then doxygen will immediately stop when -# a warning is encountered. -# The default value is: NO. - -WARN_AS_ERROR = NO - -# The WARN_FORMAT tag determines the format of the warning messages that doxygen -# can produce. The string should contain the $file, $line, and $text tags, which -# will be replaced by the file and line number from which the warning originated -# and the warning text. Optionally the format may contain $version, which will -# be replaced by the version of the file (if it could be obtained via -# FILE_VERSION_FILTER) -# The default value is: $file:$line: $text. - -WARN_FORMAT = "$file:$line: $text" - -# The WARN_LOGFILE tag can be used to specify a file to which warning and error -# messages should be written. If left blank the output is written to standard -# error (stderr). - -WARN_LOGFILE = - -#--------------------------------------------------------------------------- -# Configuration options related to the input files -#--------------------------------------------------------------------------- - -# The INPUT tag is used to specify the files and/or directories that contain -# documented source files. You may enter file names like myfile.cpp or -# directories like /usr/src/myproject. Separate the files or directories with -# spaces. See also FILE_PATTERNS and EXTENSION_MAPPING -# Note: If this tag is empty the current directory is searched. - -INPUT = README.md . - -# This tag can be used to specify the character encoding of the source files -# that doxygen parses. Internally doxygen uses the UTF-8 encoding. Doxygen uses -# libiconv (or the iconv built into libc) for the transcoding. See the libiconv -# documentation (see: https://www.gnu.org/software/libiconv/) for the list of -# possible encodings. -# The default value is: UTF-8. - -INPUT_ENCODING = UTF-8 - -# If the value of the INPUT tag contains directories, you can use the -# FILE_PATTERNS tag to specify one or more wildcard patterns (like *.cpp and -# *.h) to filter out the source-files in the directories. -# -# Note that for custom extensions or not directly supported extensions you also -# need to set EXTENSION_MAPPING for the extension otherwise the files are not -# read by doxygen. -# -# If left blank the following patterns are tested:*.c, *.cc, *.cxx, *.cpp, -# *.c++, *.java, *.ii, *.ixx, *.ipp, *.i++, *.inl, *.idl, *.ddl, *.odl, *.h, -# *.hh, *.hxx, *.hpp, *.h++, *.cs, *.d, *.php, *.php4, *.php5, *.phtml, *.inc, -# *.m, *.markdown, *.md, *.mm, *.dox (to be provided as doxygen C comment), -# *.doc (to be provided as doxygen C comment), *.txt (to be provided as doxygen -# C comment), *.py, *.pyw, *.f90, *.f95, *.f03, *.f08, *.f, *.for, *.tcl, *.vhd, -# *.vhdl, *.ucf, *.qsf and *.ice. - -FILE_PATTERNS = *.c \ - *.cc \ - *.cxx \ - *.cpp \ - *.c++ \ - *.java \ - *.ii \ - *.ixx \ - *.ipp \ - *.i++ \ - *.inl \ - *.idl \ - *.ddl \ - *.odl \ - *.h \ - *.hh \ - *.hxx \ - *.hpp \ - *.h++ \ - *.cs \ - *.d \ - *.php \ - *.php4 \ - *.php5 \ - *.phtml \ - *.inc \ - *.m \ - *.markdown \ - *.md \ - *.mm \ - *.dox \ - *.doc \ - *.txt \ - *.py \ - *.pyw \ - *.f90 \ - *.f95 \ - *.f03 \ - *.f08 \ - *.f \ - *.for \ - *.tcl \ - *.vhd \ - *.vhdl \ - *.ucf \ - *.qsf \ - *.ice - -# The RECURSIVE tag can be used to specify whether or not subdirectories should -# be searched for input files as well. -# The default value is: NO. - -RECURSIVE = YES - -# The EXCLUDE tag can be used to specify files and/or directories that should be -# excluded from the INPUT source files. This way you can easily exclude a -# subdirectory from a directory tree whose root is specified with the INPUT tag. -# -# Note that relative paths are relative to the directory from which doxygen is -# run. - -EXCLUDE = - -# The EXCLUDE_SYMLINKS tag can be used to select whether or not files or -# directories that are symbolic links (a Unix file system feature) are excluded -# from the input. -# The default value is: NO. - -EXCLUDE_SYMLINKS = NO - -# If the value of the INPUT tag contains directories, you can use the -# EXCLUDE_PATTERNS tag to specify one or more wildcard patterns to exclude -# certain files from those directories. -# -# Note that the wildcards are matched against the file with absolute path, so to -# exclude all test directories for example use the pattern */test/* - -EXCLUDE_PATTERNS = - -# The EXCLUDE_SYMBOLS tag can be used to specify one or more symbol names -# (namespaces, classes, functions, etc.) that should be excluded from the -# output. The symbol name can be a fully qualified name, a word, or if the -# wildcard * is used, a substring. Examples: ANamespace, AClass, -# AClass::ANamespace, ANamespace::*Test -# -# Note that the wildcards are matched against the file with absolute path, so to -# exclude all test directories use the pattern */test/* - -EXCLUDE_SYMBOLS = - -# The EXAMPLE_PATH tag can be used to specify one or more files or directories -# that contain example code fragments that are included (see the \include -# command). - -EXAMPLE_PATH = - -# If the value of the EXAMPLE_PATH tag contains directories, you can use the -# EXAMPLE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp and -# *.h) to filter out the source-files in the directories. If left blank all -# files are included. - -EXAMPLE_PATTERNS = * - -# If the EXAMPLE_RECURSIVE tag is set to YES then subdirectories will be -# searched for input files to be used with the \include or \dontinclude commands -# irrespective of the value of the RECURSIVE tag. -# The default value is: NO. - -EXAMPLE_RECURSIVE = NO - -# The IMAGE_PATH tag can be used to specify one or more files or directories -# that contain images that are to be included in the documentation (see the -# \image command). - -IMAGE_PATH = - -# The INPUT_FILTER tag can be used to specify a program that doxygen should -# invoke to filter for each input file. Doxygen will invoke the filter program -# by executing (via popen()) the command: -# -# -# -# where is the value of the INPUT_FILTER tag, and is the -# name of an input file. Doxygen will then use the output that the filter -# program writes to standard output. If FILTER_PATTERNS is specified, this tag -# will be ignored. -# -# Note that the filter must not add or remove lines; it is applied before the -# code is scanned, but not when the output code is generated. If lines are added -# or removed, the anchors will not be placed correctly. -# -# Note that for custom extensions or not directly supported extensions you also -# need to set EXTENSION_MAPPING for the extension otherwise the files are not -# properly processed by doxygen. - -INPUT_FILTER = - -# The FILTER_PATTERNS tag can be used to specify filters on a per file pattern -# basis. Doxygen will compare the file name with each pattern and apply the -# filter if there is a match. The filters are a list of the form: pattern=filter -# (like *.cpp=my_cpp_filter). See INPUT_FILTER for further information on how -# filters are used. If the FILTER_PATTERNS tag is empty or if none of the -# patterns match the file name, INPUT_FILTER is applied. -# -# Note that for custom extensions or not directly supported extensions you also -# need to set EXTENSION_MAPPING for the extension otherwise the files are not -# properly processed by doxygen. - -FILTER_PATTERNS = - -# If the FILTER_SOURCE_FILES tag is set to YES, the input filter (if set using -# INPUT_FILTER) will also be used to filter the input files that are used for -# producing the source files to browse (i.e. when SOURCE_BROWSER is set to YES). -# The default value is: NO. - -FILTER_SOURCE_FILES = NO - -# The FILTER_SOURCE_PATTERNS tag can be used to specify source filters per file -# pattern. A pattern will override the setting for FILTER_PATTERN (if any) and -# it is also possible to disable source filtering for a specific pattern using -# *.ext= (so without naming a filter). -# This tag requires that the tag FILTER_SOURCE_FILES is set to YES. - -FILTER_SOURCE_PATTERNS = - -# If the USE_MDFILE_AS_MAINPAGE tag refers to the name of a markdown file that -# is part of the input, its contents will be placed on the main page -# (index.html). This can be useful if you have a project on for instance GitHub -# and want to reuse the introduction page also for the doxygen output. - -USE_MDFILE_AS_MAINPAGE = README.md - -#--------------------------------------------------------------------------- -# Configuration options related to source browsing -#--------------------------------------------------------------------------- - -# If the SOURCE_BROWSER tag is set to YES then a list of source files will be -# generated. Documented entities will be cross-referenced with these sources. -# -# Note: To get rid of all source code in the generated output, make sure that -# also VERBATIM_HEADERS is set to NO. -# The default value is: NO. - -SOURCE_BROWSER = NO - -# Setting the INLINE_SOURCES tag to YES will include the body of functions, -# classes and enums directly into the documentation. -# The default value is: NO. - -INLINE_SOURCES = NO - -# Setting the STRIP_CODE_COMMENTS tag to YES will instruct doxygen to hide any -# special comment blocks from generated source code fragments. Normal C, C++ and -# Fortran comments will always remain visible. -# The default value is: YES. - -STRIP_CODE_COMMENTS = YES - -# If the REFERENCED_BY_RELATION tag is set to YES then for each documented -# entity all documented functions referencing it will be listed. -# The default value is: NO. - -REFERENCED_BY_RELATION = NO - -# If the REFERENCES_RELATION tag is set to YES then for each documented function -# all documented entities called/used by that function will be listed. -# The default value is: NO. - -REFERENCES_RELATION = NO - -# If the REFERENCES_LINK_SOURCE tag is set to YES and SOURCE_BROWSER tag is set -# to YES then the hyperlinks from functions in REFERENCES_RELATION and -# REFERENCED_BY_RELATION lists will link to the source code. Otherwise they will -# link to the documentation. -# The default value is: YES. - -REFERENCES_LINK_SOURCE = YES - -# If SOURCE_TOOLTIPS is enabled (the default) then hovering a hyperlink in the -# source code will show a tooltip with additional information such as prototype, -# brief description and links to the definition and documentation. Since this -# will make the HTML file larger and loading of large files a bit slower, you -# can opt to disable this feature. -# The default value is: YES. -# This tag requires that the tag SOURCE_BROWSER is set to YES. - -SOURCE_TOOLTIPS = YES - -# If the USE_HTAGS tag is set to YES then the references to source code will -# point to the HTML generated by the htags(1) tool instead of doxygen built-in -# source browser. The htags tool is part of GNU's global source tagging system -# (see https://www.gnu.org/software/global/global.html). You will need version -# 4.8.6 or higher. -# -# To use it do the following: -# - Install the latest version of global -# - Enable SOURCE_BROWSER and USE_HTAGS in the configuration file -# - Make sure the INPUT points to the root of the source tree -# - Run doxygen as normal -# -# Doxygen will invoke htags (and that will in turn invoke gtags), so these -# tools must be available from the command line (i.e. in the search path). -# -# The result: instead of the source browser generated by doxygen, the links to -# source code will now point to the output of htags. -# The default value is: NO. -# This tag requires that the tag SOURCE_BROWSER is set to YES. - -USE_HTAGS = NO - -# If the VERBATIM_HEADERS tag is set the YES then doxygen will generate a -# verbatim copy of the header file for each class for which an include is -# specified. Set to NO to disable this. -# See also: Section \class. -# The default value is: YES. - -VERBATIM_HEADERS = YES - -# If the CLANG_ASSISTED_PARSING tag is set to YES then doxygen will use the -# clang parser (see: http://clang.llvm.org/) for more accurate parsing at the -# cost of reduced performance. This can be particularly helpful with template -# rich C++ code for which doxygen's built-in parser lacks the necessary type -# information. -# Note: The availability of this option depends on whether or not doxygen was -# generated with the -Duse_libclang=ON option for CMake. -# The default value is: NO. - -CLANG_ASSISTED_PARSING = NO - -# If clang assisted parsing is enabled you can provide the compiler with command -# line options that you would normally use when invoking the compiler. Note that -# the include paths will already be set by doxygen for the files and directories -# specified with INPUT and INCLUDE_PATH. -# This tag requires that the tag CLANG_ASSISTED_PARSING is set to YES. - -CLANG_OPTIONS = - -# If clang assisted parsing is enabled you can provide the clang parser with the -# path to the compilation database (see: -# http://clang.llvm.org/docs/HowToSetupToolingForLLVM.html) used when the files -# were built. This is equivalent to specifying the "-p" option to a clang tool, -# such as clang-check. These options will then be passed to the parser. -# Note: The availability of this option depends on whether or not doxygen was -# generated with the -Duse_libclang=ON option for CMake. - -CLANG_DATABASE_PATH = - -#--------------------------------------------------------------------------- -# Configuration options related to the alphabetical class index -#--------------------------------------------------------------------------- - -# If the ALPHABETICAL_INDEX tag is set to YES, an alphabetical index of all -# compounds will be generated. Enable this if the project contains a lot of -# classes, structs, unions or interfaces. -# The default value is: YES. - -ALPHABETICAL_INDEX = YES - -# The COLS_IN_ALPHA_INDEX tag can be used to specify the number of columns in -# which the alphabetical index list will be split. -# Minimum value: 1, maximum value: 20, default value: 5. -# This tag requires that the tag ALPHABETICAL_INDEX is set to YES. - -COLS_IN_ALPHA_INDEX = 5 - -# In case all classes in a project start with a common prefix, all classes will -# be put under the same header in the alphabetical index. The IGNORE_PREFIX tag -# can be used to specify a prefix (or a list of prefixes) that should be ignored -# while generating the index headers. -# This tag requires that the tag ALPHABETICAL_INDEX is set to YES. - -IGNORE_PREFIX = - -#--------------------------------------------------------------------------- -# Configuration options related to the HTML output -#--------------------------------------------------------------------------- - -# If the GENERATE_HTML tag is set to YES, doxygen will generate HTML output -# The default value is: YES. - -GENERATE_HTML = YES - -# The HTML_OUTPUT tag is used to specify where the HTML docs will be put. If a -# relative path is entered the value of OUTPUT_DIRECTORY will be put in front of -# it. -# The default directory is: html. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_OUTPUT = html - -# The HTML_FILE_EXTENSION tag can be used to specify the file extension for each -# generated HTML page (for example: .htm, .php, .asp). -# The default value is: .html. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_FILE_EXTENSION = .html - -# The HTML_HEADER tag can be used to specify a user-defined HTML header file for -# each generated HTML page. If the tag is left blank doxygen will generate a -# standard header. -# -# To get valid HTML the header file that includes any scripts and style sheets -# that doxygen needs, which is dependent on the configuration options used (e.g. -# the setting GENERATE_TREEVIEW). It is highly recommended to start with a -# default header using -# doxygen -w html new_header.html new_footer.html new_stylesheet.css -# YourConfigFile -# and then modify the file new_header.html. See also section "Doxygen usage" -# for information on how to generate the default header that doxygen normally -# uses. -# Note: The header is subject to change so you typically have to regenerate the -# default header when upgrading to a newer version of doxygen. For a description -# of the possible markers and block names see the documentation. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_HEADER = - -# The HTML_FOOTER tag can be used to specify a user-defined HTML footer for each -# generated HTML page. If the tag is left blank doxygen will generate a standard -# footer. See HTML_HEADER for more information on how to generate a default -# footer and what special commands can be used inside the footer. See also -# section "Doxygen usage" for information on how to generate the default footer -# that doxygen normally uses. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_FOOTER = - -# The HTML_STYLESHEET tag can be used to specify a user-defined cascading style -# sheet that is used by each HTML page. It can be used to fine-tune the look of -# the HTML output. If left blank doxygen will generate a default style sheet. -# See also section "Doxygen usage" for information on how to generate the style -# sheet that doxygen normally uses. -# Note: It is recommended to use HTML_EXTRA_STYLESHEET instead of this tag, as -# it is more robust and this tag (HTML_STYLESHEET) will in the future become -# obsolete. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_STYLESHEET = - -# The HTML_EXTRA_STYLESHEET tag can be used to specify additional user-defined -# cascading style sheets that are included after the standard style sheets -# created by doxygen. Using this option one can overrule certain style aspects. -# This is preferred over using HTML_STYLESHEET since it does not replace the -# standard style sheet and is therefore more robust against future updates. -# Doxygen will copy the style sheet files to the output directory. -# Note: The order of the extra style sheet files is of importance (e.g. the last -# style sheet in the list overrules the setting of the previous ones in the -# list). For an example see the documentation. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_EXTRA_STYLESHEET = - -# The HTML_EXTRA_FILES tag can be used to specify one or more extra images or -# other source files which should be copied to the HTML output directory. Note -# that these files will be copied to the base HTML output directory. Use the -# $relpath^ marker in the HTML_HEADER and/or HTML_FOOTER files to load these -# files. In the HTML_STYLESHEET file, use the file name only. Also note that the -# files will be copied as-is; there are no commands or markers available. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_EXTRA_FILES = - -# The HTML_COLORSTYLE_HUE tag controls the color of the HTML output. Doxygen -# will adjust the colors in the style sheet and background images according to -# this color. Hue is specified as an angle on a colorwheel, see -# https://en.wikipedia.org/wiki/Hue for more information. For instance the value -# 0 represents red, 60 is yellow, 120 is green, 180 is cyan, 240 is blue, 300 -# purple, and 360 is red again. -# Minimum value: 0, maximum value: 359, default value: 220. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_COLORSTYLE_HUE = 220 - -# The HTML_COLORSTYLE_SAT tag controls the purity (or saturation) of the colors -# in the HTML output. For a value of 0 the output will use grayscales only. A -# value of 255 will produce the most vivid colors. -# Minimum value: 0, maximum value: 255, default value: 100. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_COLORSTYLE_SAT = 100 - -# The HTML_COLORSTYLE_GAMMA tag controls the gamma correction applied to the -# luminance component of the colors in the HTML output. Values below 100 -# gradually make the output lighter, whereas values above 100 make the output -# darker. The value divided by 100 is the actual gamma applied, so 80 represents -# a gamma of 0.8, The value 220 represents a gamma of 2.2, and 100 does not -# change the gamma. -# Minimum value: 40, maximum value: 240, default value: 80. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_COLORSTYLE_GAMMA = 80 - -# If the HTML_TIMESTAMP tag is set to YES then the footer of each generated HTML -# page will contain the date and time when the page was generated. Setting this -# to YES can help to show when doxygen was last run and thus if the -# documentation is up to date. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_TIMESTAMP = NO - -# If the HTML_DYNAMIC_MENUS tag is set to YES then the generated HTML -# documentation will contain a main index with vertical navigation menus that -# are dynamically created via JavaScript. If disabled, the navigation index will -# consists of multiple levels of tabs that are statically embedded in every HTML -# page. Disable this option to support browsers that do not have JavaScript, -# like the Qt help browser. -# The default value is: YES. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_DYNAMIC_MENUS = YES - -# If the HTML_DYNAMIC_SECTIONS tag is set to YES then the generated HTML -# documentation will contain sections that can be hidden and shown after the -# page has loaded. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_DYNAMIC_SECTIONS = NO - -# With HTML_INDEX_NUM_ENTRIES one can control the preferred number of entries -# shown in the various tree structured indices initially; the user can expand -# and collapse entries dynamically later on. Doxygen will expand the tree to -# such a level that at most the specified number of entries are visible (unless -# a fully collapsed tree already exceeds this amount). So setting the number of -# entries 1 will produce a full collapsed tree by default. 0 is a special value -# representing an infinite number of entries and will result in a full expanded -# tree by default. -# Minimum value: 0, maximum value: 9999, default value: 100. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_INDEX_NUM_ENTRIES = 100 - -# If the GENERATE_DOCSET tag is set to YES, additional index files will be -# generated that can be used as input for Apple's Xcode 3 integrated development -# environment (see: https://developer.apple.com/xcode/), introduced with OSX -# 10.5 (Leopard). To create a documentation set, doxygen will generate a -# Makefile in the HTML output directory. Running make will produce the docset in -# that directory and running make install will install the docset in -# ~/Library/Developer/Shared/Documentation/DocSets so that Xcode will find it at -# startup. See https://developer.apple.com/library/archive/featuredarticles/Doxy -# genXcode/_index.html for more information. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -GENERATE_DOCSET = NO - -# This tag determines the name of the docset feed. A documentation feed provides -# an umbrella under which multiple documentation sets from a single provider -# (such as a company or product suite) can be grouped. -# The default value is: Doxygen generated docs. -# This tag requires that the tag GENERATE_DOCSET is set to YES. - -DOCSET_FEEDNAME = "Doxygen generated docs" - -# This tag specifies a string that should uniquely identify the documentation -# set bundle. This should be a reverse domain-name style string, e.g. -# com.mycompany.MyDocSet. Doxygen will append .docset to the name. -# The default value is: org.doxygen.Project. -# This tag requires that the tag GENERATE_DOCSET is set to YES. - -DOCSET_BUNDLE_ID = org.doxygen.Project - -# The DOCSET_PUBLISHER_ID tag specifies a string that should uniquely identify -# the documentation publisher. This should be a reverse domain-name style -# string, e.g. com.mycompany.MyDocSet.documentation. -# The default value is: org.doxygen.Publisher. -# This tag requires that the tag GENERATE_DOCSET is set to YES. - -DOCSET_PUBLISHER_ID = org.doxygen.Publisher - -# The DOCSET_PUBLISHER_NAME tag identifies the documentation publisher. -# The default value is: Publisher. -# This tag requires that the tag GENERATE_DOCSET is set to YES. - -DOCSET_PUBLISHER_NAME = Publisher - -# If the GENERATE_HTMLHELP tag is set to YES then doxygen generates three -# additional HTML index files: index.hhp, index.hhc, and index.hhk. The -# index.hhp is a project file that can be read by Microsoft's HTML Help Workshop -# (see: https://www.microsoft.com/en-us/download/details.aspx?id=21138) on -# Windows. -# -# The HTML Help Workshop contains a compiler that can convert all HTML output -# generated by doxygen into a single compiled HTML file (.chm). Compiled HTML -# files are now used as the Windows 98 help format, and will replace the old -# Windows help format (.hlp) on all Windows platforms in the future. Compressed -# HTML files also contain an index, a table of contents, and you can search for -# words in the documentation. The HTML workshop also contains a viewer for -# compressed HTML files. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -GENERATE_HTMLHELP = NO - -# The CHM_FILE tag can be used to specify the file name of the resulting .chm -# file. You can add a path in front of the file if the result should not be -# written to the html output directory. -# This tag requires that the tag GENERATE_HTMLHELP is set to YES. - -CHM_FILE = - -# The HHC_LOCATION tag can be used to specify the location (absolute path -# including file name) of the HTML help compiler (hhc.exe). If non-empty, -# doxygen will try to run the HTML help compiler on the generated index.hhp. -# The file has to be specified with full path. -# This tag requires that the tag GENERATE_HTMLHELP is set to YES. - -HHC_LOCATION = - -# The GENERATE_CHI flag controls if a separate .chi index file is generated -# (YES) or that it should be included in the master .chm file (NO). -# The default value is: NO. -# This tag requires that the tag GENERATE_HTMLHELP is set to YES. - -GENERATE_CHI = NO - -# The CHM_INDEX_ENCODING is used to encode HtmlHelp index (hhk), content (hhc) -# and project file content. -# This tag requires that the tag GENERATE_HTMLHELP is set to YES. - -CHM_INDEX_ENCODING = - -# The BINARY_TOC flag controls whether a binary table of contents is generated -# (YES) or a normal table of contents (NO) in the .chm file. Furthermore it -# enables the Previous and Next buttons. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTMLHELP is set to YES. - -BINARY_TOC = NO - -# The TOC_EXPAND flag can be set to YES to add extra items for group members to -# the table of contents of the HTML help documentation and to the tree view. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTMLHELP is set to YES. - -TOC_EXPAND = NO - -# If the GENERATE_QHP tag is set to YES and both QHP_NAMESPACE and -# QHP_VIRTUAL_FOLDER are set, an additional index file will be generated that -# can be used as input for Qt's qhelpgenerator to generate a Qt Compressed Help -# (.qch) of the generated HTML documentation. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -GENERATE_QHP = NO - -# If the QHG_LOCATION tag is specified, the QCH_FILE tag can be used to specify -# the file name of the resulting .qch file. The path specified is relative to -# the HTML output folder. -# This tag requires that the tag GENERATE_QHP is set to YES. - -QCH_FILE = - -# The QHP_NAMESPACE tag specifies the namespace to use when generating Qt Help -# Project output. For more information please see Qt Help Project / Namespace -# (see: https://doc.qt.io/archives/qt-4.8/qthelpproject.html#namespace). -# The default value is: org.doxygen.Project. -# This tag requires that the tag GENERATE_QHP is set to YES. - -QHP_NAMESPACE = org.doxygen.Project - -# The QHP_VIRTUAL_FOLDER tag specifies the namespace to use when generating Qt -# Help Project output. For more information please see Qt Help Project / Virtual -# Folders (see: https://doc.qt.io/archives/qt-4.8/qthelpproject.html#virtual- -# folders). -# The default value is: doc. -# This tag requires that the tag GENERATE_QHP is set to YES. - -QHP_VIRTUAL_FOLDER = doc - -# If the QHP_CUST_FILTER_NAME tag is set, it specifies the name of a custom -# filter to add. For more information please see Qt Help Project / Custom -# Filters (see: https://doc.qt.io/archives/qt-4.8/qthelpproject.html#custom- -# filters). -# This tag requires that the tag GENERATE_QHP is set to YES. - -QHP_CUST_FILTER_NAME = - -# The QHP_CUST_FILTER_ATTRS tag specifies the list of the attributes of the -# custom filter to add. For more information please see Qt Help Project / Custom -# Filters (see: https://doc.qt.io/archives/qt-4.8/qthelpproject.html#custom- -# filters). -# This tag requires that the tag GENERATE_QHP is set to YES. - -QHP_CUST_FILTER_ATTRS = - -# The QHP_SECT_FILTER_ATTRS tag specifies the list of the attributes this -# project's filter section matches. Qt Help Project / Filter Attributes (see: -# https://doc.qt.io/archives/qt-4.8/qthelpproject.html#filter-attributes). -# This tag requires that the tag GENERATE_QHP is set to YES. - -QHP_SECT_FILTER_ATTRS = - -# The QHG_LOCATION tag can be used to specify the location of Qt's -# qhelpgenerator. If non-empty doxygen will try to run qhelpgenerator on the -# generated .qhp file. -# This tag requires that the tag GENERATE_QHP is set to YES. - -QHG_LOCATION = - -# If the GENERATE_ECLIPSEHELP tag is set to YES, additional index files will be -# generated, together with the HTML files, they form an Eclipse help plugin. To -# install this plugin and make it available under the help contents menu in -# Eclipse, the contents of the directory containing the HTML and XML files needs -# to be copied into the plugins directory of eclipse. The name of the directory -# within the plugins directory should be the same as the ECLIPSE_DOC_ID value. -# After copying Eclipse needs to be restarted before the help appears. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -GENERATE_ECLIPSEHELP = NO - -# A unique identifier for the Eclipse help plugin. When installing the plugin -# the directory name containing the HTML and XML files should also have this -# name. Each documentation set should have its own identifier. -# The default value is: org.doxygen.Project. -# This tag requires that the tag GENERATE_ECLIPSEHELP is set to YES. - -ECLIPSE_DOC_ID = org.doxygen.Project - -# If you want full control over the layout of the generated HTML pages it might -# be necessary to disable the index and replace it with your own. The -# DISABLE_INDEX tag can be used to turn on/off the condensed index (tabs) at top -# of each HTML page. A value of NO enables the index and the value YES disables -# it. Since the tabs in the index contain the same information as the navigation -# tree, you can set this option to YES if you also set GENERATE_TREEVIEW to YES. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -DISABLE_INDEX = NO - -# The GENERATE_TREEVIEW tag is used to specify whether a tree-like index -# structure should be generated to display hierarchical information. If the tag -# value is set to YES, a side panel will be generated containing a tree-like -# index structure (just like the one that is generated for HTML Help). For this -# to work a browser that supports JavaScript, DHTML, CSS and frames is required -# (i.e. any modern browser). Windows users are probably better off using the -# HTML help feature. Via custom style sheets (see HTML_EXTRA_STYLESHEET) one can -# further fine-tune the look of the index. As an example, the default style -# sheet generated by doxygen has an example that shows how to put an image at -# the root of the tree instead of the PROJECT_NAME. Since the tree basically has -# the same information as the tab index, you could consider setting -# DISABLE_INDEX to YES when enabling this option. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -GENERATE_TREEVIEW = NO - -# The ENUM_VALUES_PER_LINE tag can be used to set the number of enum values that -# doxygen will group on one line in the generated HTML documentation. -# -# Note that a value of 0 will completely suppress the enum values from appearing -# in the overview section. -# Minimum value: 0, maximum value: 20, default value: 4. -# This tag requires that the tag GENERATE_HTML is set to YES. - -ENUM_VALUES_PER_LINE = 4 - -# If the treeview is enabled (see GENERATE_TREEVIEW) then this tag can be used -# to set the initial width (in pixels) of the frame in which the tree is shown. -# Minimum value: 0, maximum value: 1500, default value: 250. -# This tag requires that the tag GENERATE_HTML is set to YES. - -TREEVIEW_WIDTH = 250 - -# If the EXT_LINKS_IN_WINDOW option is set to YES, doxygen will open links to -# external symbols imported via tag files in a separate window. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -EXT_LINKS_IN_WINDOW = NO - -# Use this tag to change the font size of LaTeX formulas included as images in -# the HTML documentation. When you change the font size after a successful -# doxygen run you need to manually remove any form_*.png images from the HTML -# output directory to force them to be regenerated. -# Minimum value: 8, maximum value: 50, default value: 10. -# This tag requires that the tag GENERATE_HTML is set to YES. - -FORMULA_FONTSIZE = 10 - -# Use the FORMULA_TRANSPARENT tag to determine whether or not the images -# generated for formulas are transparent PNGs. Transparent PNGs are not -# supported properly for IE 6.0, but are supported on all modern browsers. -# -# Note that when changing this option you need to delete any form_*.png files in -# the HTML output directory before the changes have effect. -# The default value is: YES. -# This tag requires that the tag GENERATE_HTML is set to YES. - -FORMULA_TRANSPARENT = YES - -# The FORMULA_MACROFILE can contain LaTeX \newcommand and \renewcommand commands -# to create new LaTeX commands to be used in formulas as building blocks. See -# the section "Including formulas" for details. - -FORMULA_MACROFILE = - -# Enable the USE_MATHJAX option to render LaTeX formulas using MathJax (see -# https://www.mathjax.org) which uses client side JavaScript for the rendering -# instead of using pre-rendered bitmaps. Use this if you do not have LaTeX -# installed or if you want to formulas look prettier in the HTML output. When -# enabled you may also need to install MathJax separately and configure the path -# to it using the MATHJAX_RELPATH option. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -USE_MATHJAX = NO - -# When MathJax is enabled you can set the default output format to be used for -# the MathJax output. See the MathJax site (see: -# http://docs.mathjax.org/en/latest/output.html) for more details. -# Possible values are: HTML-CSS (which is slower, but has the best -# compatibility), NativeMML (i.e. MathML) and SVG. -# The default value is: HTML-CSS. -# This tag requires that the tag USE_MATHJAX is set to YES. - -MATHJAX_FORMAT = HTML-CSS - -# When MathJax is enabled you need to specify the location relative to the HTML -# output directory using the MATHJAX_RELPATH option. The destination directory -# should contain the MathJax.js script. For instance, if the mathjax directory -# is located at the same level as the HTML output directory, then -# MATHJAX_RELPATH should be ../mathjax. The default value points to the MathJax -# Content Delivery Network so you can quickly see the result without installing -# MathJax. However, it is strongly recommended to install a local copy of -# MathJax from https://www.mathjax.org before deployment. -# The default value is: https://cdnjs.cloudflare.com/ajax/libs/mathjax/2.7.5/. -# This tag requires that the tag USE_MATHJAX is set to YES. - -MATHJAX_RELPATH = https://cdnjs.cloudflare.com/ajax/libs/mathjax/2.7.5/ - -# The MATHJAX_EXTENSIONS tag can be used to specify one or more MathJax -# extension names that should be enabled during MathJax rendering. For example -# MATHJAX_EXTENSIONS = TeX/AMSmath TeX/AMSsymbols -# This tag requires that the tag USE_MATHJAX is set to YES. - -MATHJAX_EXTENSIONS = - -# The MATHJAX_CODEFILE tag can be used to specify a file with javascript pieces -# of code that will be used on startup of the MathJax code. See the MathJax site -# (see: http://docs.mathjax.org/en/latest/output.html) for more details. For an -# example see the documentation. -# This tag requires that the tag USE_MATHJAX is set to YES. - -MATHJAX_CODEFILE = - -# When the SEARCHENGINE tag is enabled doxygen will generate a search box for -# the HTML output. The underlying search engine uses javascript and DHTML and -# should work on any modern browser. Note that when using HTML help -# (GENERATE_HTMLHELP), Qt help (GENERATE_QHP), or docsets (GENERATE_DOCSET) -# there is already a search function so this one should typically be disabled. -# For large projects the javascript based search engine can be slow, then -# enabling SERVER_BASED_SEARCH may provide a better solution. It is possible to -# search using the keyboard; to jump to the search box use + S -# (what the is depends on the OS and browser, but it is typically -# , /