diff --git a/pytest.ini b/pytest.ini new file mode 100644 index 0000000..fe55d2e --- /dev/null +++ b/pytest.ini @@ -0,0 +1,2 @@ +[pytest] +junit_family=xunit2 diff --git a/system_modes/CMakeLists.txt b/system_modes/CMakeLists.txt index 2c0bf30..c882430 100644 --- a/system_modes/CMakeLists.txt +++ b/system_modes/CMakeLists.txt @@ -18,11 +18,12 @@ endif() # find dependencies find_package(ament_cmake REQUIRED) find_package(builtin_interfaces REQUIRED) -find_package(rclcpp REQUIRED) +find_package(lifecycle_msgs REQUIRED) find_package(rcl_lifecycle REQUIRED) +find_package(rclcpp REQUIRED) find_package(rclcpp_lifecycle REQUIRED) find_package(rosidl_typesupport_cpp REQUIRED) -find_package(lifecycle_msgs REQUIRED) +find_package(std_msgs REQUIRED) find_package(system_modes_msgs REQUIRED) add_library(mode SHARED @@ -40,12 +41,12 @@ ament_target_dependencies(mode "rclcpp_lifecycle" "rosidl_typesupport_cpp" "lifecycle_msgs" + "std_msgs" "system_modes_msgs" -) - + "builtin_interfaces") # Causes the visibility macros to use dllexport rather than dllimport, # which is appropriate when building the dll but not consuming it. -target_compile_definitions(mode PRIVATE "SYSTEMMODES_BUILDING_LIBRARY") +target_compile_definitions(mode PRIVATE "SYSTEM_MODES_BUILDING_LIBRARY") install( DIRECTORY include/ diff --git a/system_modes/include/system_modes/mode.hpp b/system_modes/include/system_modes/mode.hpp index 34f5e11..12b7270 100644 --- a/system_modes/include/system_modes/mode.hpp +++ b/system_modes/include/system_modes/mode.hpp @@ -28,6 +28,8 @@ #include #include +#include "system_modes/visibility_control.hpp" + namespace system_modes { @@ -45,27 +47,57 @@ using ModeMap = std::map; class ModeBase { public: + SYSTEM_MODES_PUBLIC explicit ModeBase(const std::string & mode_name); + + SYSTEM_MODES_PUBLIC virtual ~ModeBase() = default; + // cppcheck-suppress unknownMacro - RCLCPP_DISABLE_COPY(ModeBase) + SYSTEM_MODES_PUBLIC + RCLCPP_DISABLE_COPY(ModeBase) - std::string get_name() const; + SYSTEM_MODES_PUBLIC + std::string + get_name() const; - virtual void set_parameter(const rclcpp::Parameter & parameter) = 0; - virtual void set_parameters(const std::vector & parameters) = 0; - virtual void set_part_mode( + SYSTEM_MODES_PUBLIC + virtual void + set_parameter(const rclcpp::Parameter & parameter) = 0; + + SYSTEM_MODES_PUBLIC + virtual void + set_parameters(const std::vector & parameters) = 0; + + SYSTEM_MODES_PUBLIC + virtual void + set_part_mode( const std::string & part, const StateAndMode stateAndMode) = 0; - virtual rclcpp::Parameter get_parameter(const std::string & param_name) const; - virtual std::vector get_parameter_names() const; - virtual const std::vector get_parameters() const; + SYSTEM_MODES_PUBLIC + virtual rclcpp::Parameter + get_parameter(const std::string & param_name) const; + + SYSTEM_MODES_PUBLIC + virtual std::vector + get_parameter_names() const; - virtual const std::vector get_parts() const; - virtual const StateAndMode get_part_mode(const std::string & part) const; + SYSTEM_MODES_PUBLIC + virtual const std::vector + get_parameters() const; - virtual std::string print() const; + SYSTEM_MODES_PUBLIC + virtual const std::vector + get_parts() const; + + SYSTEM_MODES_PUBLIC + virtual const StateAndMode + get_part_mode(const std::string & part) const; + + SYSTEM_MODES_PUBLIC + virtual std::string + print() const; protected: ModeImpl mode_impl_; @@ -74,15 +106,25 @@ class ModeBase class DefaultMode : public ModeBase { public: + SYSTEM_MODES_PUBLIC DefaultMode(); + + SYSTEM_MODES_PUBLIC explicit DefaultMode(const std::string & mode_name) = delete; // cppcheck-suppress unknownMacro RCLCPP_DISABLE_COPY(DefaultMode) - virtual void set_parameter(const rclcpp::Parameter & parameter); - virtual void set_parameters(const std::vector & parameters); + SYSTEM_MODES_PUBLIC + virtual void + set_parameter(const rclcpp::Parameter & parameter); - virtual void set_part_mode( + SYSTEM_MODES_PUBLIC + virtual void + set_parameters(const std::vector & parameters); + + SYSTEM_MODES_PUBLIC + virtual void + set_part_mode( const std::string & part, const StateAndMode stateAndMode); }; @@ -90,22 +132,36 @@ class DefaultMode : public ModeBase class Mode : public ModeBase { public: + SYSTEM_MODES_PUBLIC explicit Mode(const std::string & mode_name) = delete; + + SYSTEM_MODES_PUBLIC Mode(const std::string & mode_name, const DefaultModePtr default_mode); // cppcheck-suppress unknownMacro RCLCPP_DISABLE_COPY(Mode) - virtual ~Mode() = default; + SYSTEM_MODES_PUBLIC + virtual + ~Mode() = default; + + SYSTEM_MODES_PUBLIC + virtual void + set_parameter(const rclcpp::Parameter & parameter); - virtual void set_parameter(const rclcpp::Parameter & parameter); - virtual void set_parameters(const std::vector & parameters); + SYSTEM_MODES_PUBLIC + virtual void + set_parameters(const std::vector & parameters); - virtual void set_part_mode( + SYSTEM_MODES_PUBLIC + virtual void + set_part_mode( const std::string & part, const StateAndMode stateAndMode); }; -inline std::ostream & operator<<(std::ostream & os, const Mode & mode) +SYSTEM_MODES_PUBLIC +inline std::ostream & +operator<<(std::ostream & os, const Mode & mode) { os.precision(3); os << mode.print(); diff --git a/system_modes/include/system_modes/mode_handling.hpp b/system_modes/include/system_modes/mode_handling.hpp index 1b662f8..864c5b4 100644 --- a/system_modes/include/system_modes/mode_handling.hpp +++ b/system_modes/include/system_modes/mode_handling.hpp @@ -16,9 +16,11 @@ #include #include + #include #include + #include #include #include @@ -28,6 +30,7 @@ #include "system_modes/mode.hpp" #include "system_modes/mode_impl.hpp" +#include "system_modes/visibility_control.hpp" namespace system_modes { @@ -50,11 +53,15 @@ using RulesMap = std::map; class ModeHandling { public: + SYSTEM_MODES_PUBLIC explicit ModeHandling(const std::string & model_path); // cppcheck-suppress unknownMacro RCLCPP_DISABLE_COPY(ModeHandling) + SYSTEM_MODES_PUBLIC virtual ~ModeHandling() = default; + + SYSTEM_MODES_PUBLIC virtual const std::vector get_rules_for( const std::string & system, const StateAndMode & target); diff --git a/system_modes/include/system_modes/mode_impl.hpp b/system_modes/include/system_modes/mode_impl.hpp index 39863f4..6f3aac6 100644 --- a/system_modes/include/system_modes/mode_impl.hpp +++ b/system_modes/include/system_modes/mode_impl.hpp @@ -26,6 +26,8 @@ #include #include +#include "system_modes/visibility_control.hpp" + using lifecycle_msgs::msg::State; namespace system_modes @@ -34,26 +36,41 @@ namespace system_modes static const char DEFAULT_MODE[] = "__DEFAULT__"; -unsigned int state_id_(const std::string & state_label); -const std::string state_label_(unsigned int state_id); +SYSTEM_MODES_PUBLIC +unsigned int +state_id_(const std::string & state_label); + +SYSTEM_MODES_PUBLIC +const std::string +state_label_(unsigned int state_id); -unsigned int transition_id_(const std::string & transition_label); -const std::string transition_label_(unsigned int transition_id); +SYSTEM_MODES_PUBLIC +unsigned int +transition_id_(const std::string & transition_label); -unsigned int goal_state_(unsigned int transition_id); +SYSTEM_MODES_PUBLIC +const std::string +transition_label_(unsigned int transition_id); + +SYSTEM_MODES_PUBLIC +unsigned int +goal_state_(unsigned int transition_id); struct StateAndMode { unsigned int state; std::string mode; + SYSTEM_MODES_PUBLIC explicit StateAndMode(unsigned int newstate = 0, const std::string & newmode = "") { state = newstate; mode = newmode; } - bool operator==(const StateAndMode & cmp) const + SYSTEM_MODES_PUBLIC + bool + operator==(const StateAndMode & cmp) const { if (cmp.state != state) { return false; @@ -66,12 +83,16 @@ struct StateAndMode (mode.compare(DEFAULT_MODE) == 0 && cmp.mode.empty()); // DEFAULT_MODE the same } - bool operator!=(const StateAndMode & cmp) const + SYSTEM_MODES_PUBLIC + bool + operator!=(const StateAndMode & cmp) const { return !(*this == cmp); } - void from_string(const std::string & sam) + SYSTEM_MODES_PUBLIC + void + from_string(const std::string & sam) { auto dot = sam.find("."); if (dot != std::string::npos) { @@ -83,7 +104,9 @@ struct StateAndMode } } - std::string as_string() const + SYSTEM_MODES_PUBLIC + std::string + as_string() const { if (state != State::PRIMARY_STATE_ACTIVE || mode.empty()) { return state_label_(state); @@ -100,31 +123,71 @@ struct StateAndMode class ModeImpl { public: + SYSTEM_MODES_PUBLIC explicit ModeImpl(const std::string & mode_name); - virtual ~ModeImpl() = default; + + SYSTEM_MODES_PUBLIC + virtual + ~ModeImpl() = default; + + SYSTEM_MODES_PUBLIC ModeImpl(const ModeImpl & copy) = delete; - virtual std::string get_name() const; + SYSTEM_MODES_PUBLIC + virtual std::string + get_name() const; + + SYSTEM_MODES_PUBLIC + virtual void + add_parameter(const rclcpp::Parameter & parameter); + + SYSTEM_MODES_PUBLIC + virtual void + add_parameters(const std::vector & parameters); - virtual void add_parameter(const rclcpp::Parameter & parameter); - virtual void add_parameters(const std::vector & parameters); - virtual void add_part_mode( + SYSTEM_MODES_PUBLIC + virtual void + add_part_mode( const std::string & part, const StateAndMode stateAndMode); - virtual void set_parameter(const rclcpp::Parameter & parameter); - virtual void set_parameters(const std::vector & parameters); - virtual void set_part_mode( + SYSTEM_MODES_PUBLIC + virtual void + set_parameter(const rclcpp::Parameter & parameter); + + SYSTEM_MODES_PUBLIC + virtual void + set_parameters(const std::vector & parameters); + + SYSTEM_MODES_PUBLIC + virtual void + set_part_mode( const std::string & part, const StateAndMode stateAndMode); - virtual std::vector get_parameter_names() const; - virtual rclcpp::Parameter get_parameter(const std::string & param_name) const; - virtual bool get_parameter(const std::string & param_name, rclcpp::Parameter & parameter) const; - virtual const std::vector get_parameters() const; + SYSTEM_MODES_PUBLIC + virtual std::vector + get_parameter_names() const; + + SYSTEM_MODES_PUBLIC + virtual rclcpp::Parameter + get_parameter(const std::string & param_name) const; + + SYSTEM_MODES_PUBLIC + virtual bool + get_parameter(const std::string & param_name, rclcpp::Parameter & parameter) const; + + SYSTEM_MODES_PUBLIC + virtual const std::vector + get_parameters() const; + + SYSTEM_MODES_PUBLIC + virtual const std::vector + get_parts() const; - virtual const std::vector get_parts() const; - virtual const StateAndMode get_part_mode(const std::string & part) const; + SYSTEM_MODES_PUBLIC + virtual const StateAndMode + get_part_mode(const std::string & part) const; protected: std::string name_; diff --git a/system_modes/include/system_modes/mode_inference.hpp b/system_modes/include/system_modes/mode_inference.hpp index b02eed1..965f121 100644 --- a/system_modes/include/system_modes/mode_inference.hpp +++ b/system_modes/include/system_modes/mode_inference.hpp @@ -28,6 +28,7 @@ #include "system_modes/mode.hpp" #include "system_modes/mode_handling.hpp" +#include "system_modes/visibility_control.hpp" namespace system_modes { @@ -39,28 +40,68 @@ typedef std::map> Deviation; class ModeInference { public: + SYSTEM_MODES_PUBLIC explicit ModeInference(const std::string & model_path); + // cppcheck-suppress unknownMacro RCLCPP_DISABLE_COPY(ModeInference) - virtual const std::vector get_all_parts() const; - virtual const std::vector get_nodes() const; - virtual const std::vector get_systems() const; - virtual const std::vector get_all_parts_of( + SYSTEM_MODES_PUBLIC + virtual const std::vector + get_all_parts() const; + + SYSTEM_MODES_PUBLIC + virtual const std::vector + get_nodes() const; + + SYSTEM_MODES_PUBLIC + virtual const std::vector + get_systems() const; + + SYSTEM_MODES_PUBLIC + virtual const std::vector + get_all_parts_of( const std::string & system) const; - virtual void update(const std::string &, const StateAndMode &); - virtual void update_state(const std::string &, unsigned int); - virtual void update_mode(const std::string &, const std::string &); - virtual void update_param(const std::string &, rclcpp::Parameter &); - virtual void update_target(const std::string &, StateAndMode); + SYSTEM_MODES_PUBLIC + virtual void + update(const std::string &, const StateAndMode &); + + SYSTEM_MODES_PUBLIC + virtual void + update_state(const std::string &, unsigned int); + + SYSTEM_MODES_PUBLIC + virtual void + update_mode(const std::string &, const std::string &); + + SYSTEM_MODES_PUBLIC + virtual void + update_param(const std::string &, rclcpp::Parameter &); + + SYSTEM_MODES_PUBLIC + virtual void + update_target(const std::string &, StateAndMode); - virtual StateAndMode get(const std::string & part) const; - virtual StateAndMode get_or_infer(const std::string & part); + SYSTEM_MODES_PUBLIC + virtual StateAndMode + get(const std::string & part) const; - virtual StateAndMode infer(const std::string & part); - virtual StateAndMode infer_node(const std::string & part); - virtual StateAndMode infer_system(const std::string & part); + SYSTEM_MODES_PUBLIC + virtual StateAndMode + get_or_infer(const std::string & part); + + SYSTEM_MODES_PUBLIC + virtual StateAndMode + infer(const std::string & part); + + SYSTEM_MODES_PUBLIC + virtual StateAndMode + infer_node(const std::string & part); + + SYSTEM_MODES_PUBLIC + virtual StateAndMode + infer_system(const std::string & part); /** * Infers latest transitions of systems @@ -70,19 +111,42 @@ class ModeInference * nodes publish their state transitions. For nodes, we only need to infer * mode transitions. */ - virtual Deviation infer_transitions(); - virtual Deviation get_deviation(); + SYSTEM_MODES_PUBLIC + virtual Deviation + infer_transitions(); + + SYSTEM_MODES_PUBLIC + virtual Deviation + get_deviation(); - virtual StateAndMode get_target(const std::string & part) const; - virtual ModeConstPtr get_mode(const std::string & part, const std::string & mode) const; - virtual std::vector get_available_modes(const std::string & part) const; + SYSTEM_MODES_PUBLIC + virtual StateAndMode + get_target(const std::string & part) const; - virtual ~ModeInference() = default; + SYSTEM_MODES_PUBLIC + virtual ModeConstPtr + get_mode(const std::string & part, const std::string & mode) const; + + SYSTEM_MODES_PUBLIC + virtual std::vector + get_available_modes(const std::string & part) const; + + SYSTEM_MODES_PUBLIC + virtual + ~ModeInference() = default; protected: - virtual bool matching_parameters(const rclcpp::Parameter &, const rclcpp::Parameter &) const; - virtual void read_modes_from_model(const std::string & model_path); - virtual void add_param_to_mode(ModeBasePtr, const rclcpp::Parameter &); + SYSTEM_MODES_PUBLIC + virtual bool + matching_parameters(const rclcpp::Parameter &, const rclcpp::Parameter &) const; + + SYSTEM_MODES_PUBLIC + virtual void + read_modes_from_model(const std::string & model_path); + + SYSTEM_MODES_PUBLIC + virtual void + add_param_to_mode(ModeBasePtr, const rclcpp::Parameter &); private: ModeHandling * mode_handling_; diff --git a/system_modes/include/system_modes/mode_manager.hpp b/system_modes/include/system_modes/mode_manager.hpp index 4ee34f1..975439a 100644 --- a/system_modes/include/system_modes/mode_manager.hpp +++ b/system_modes/include/system_modes/mode_manager.hpp @@ -30,6 +30,7 @@ #include "system_modes/mode_handling.hpp" #include "system_modes/mode_inference.hpp" +#include "system_modes/visibility_control.hpp" #include "system_modes_msgs/srv/change_mode.hpp" #include "system_modes_msgs/srv/get_mode.hpp" #include "system_modes_msgs/srv/get_available_modes.hpp" @@ -41,63 +42,107 @@ namespace system_modes class ModeManager : public rclcpp::Node { public: + SYSTEM_MODES_PUBLIC ModeManager(); + + SYSTEM_MODES_PUBLIC ModeManager(const ModeManager &) = delete; - std::shared_ptr inference(); - virtual void handle_system_deviation(const std::string & reason); + SYSTEM_MODES_PUBLIC + virtual + ~ModeManager(); + + SYSTEM_MODES_PUBLIC + std::shared_ptr + inference(); - virtual ~ModeManager() = default; + SYSTEM_MODES_PUBLIC + virtual void + handle_system_deviation(const std::string & reason); protected: - virtual void add_system(const std::string &); - virtual void add_node(const std::string &); + SYSTEM_MODES_PUBLIC + virtual void + add_system(const std::string &); + + SYSTEM_MODES_PUBLIC + virtual void + add_node(const std::string &); // Lifecycle service callbacks - virtual void on_change_state( + SYSTEM_MODES_PUBLIC + virtual void + on_change_state( const std::string &, const std::shared_ptr, std::shared_ptr); - virtual void on_get_state( + + SYSTEM_MODES_PUBLIC + virtual void + on_get_state( const std::string &, std::shared_ptr); - virtual void on_get_available_states( + + SYSTEM_MODES_PUBLIC + virtual void + on_get_available_states( const std::string &, std::shared_ptr); // Mode service callbacks - virtual void on_change_mode( + SYSTEM_MODES_PUBLIC + virtual void + on_change_mode( const std::string &, const std::shared_ptr, std::shared_ptr); - virtual void on_get_mode( + + SYSTEM_MODES_PUBLIC + virtual void + on_get_mode( const std::string &, std::shared_ptr); - virtual void on_get_available_modes( + + SYSTEM_MODES_PUBLIC + virtual void + on_get_available_modes( const std::string &, std::shared_ptr); - virtual bool change_state( + SYSTEM_MODES_PUBLIC + virtual bool + change_state( const std::string &, unsigned int, bool transitive = true); - virtual bool change_mode( + + SYSTEM_MODES_PUBLIC + virtual bool + change_mode( const std::string &, const std::string &); - virtual void change_part_state( + SYSTEM_MODES_PUBLIC + virtual void + change_part_state( const std::string &, unsigned int); - virtual void change_part_mode( + + SYSTEM_MODES_PUBLIC + virtual void + change_part_mode( const std::string &, const std::string &); - virtual void publish_transitions(); + SYSTEM_MODES_PUBLIC + virtual void + publish_transitions(); private: std::shared_ptr mode_inference_; std::shared_ptr mode_handling_; rclcpp::TimerBase::SharedPtr periodic_timer_; + std::string model_path_; // Lifecycle change services diff --git a/system_modes/include/system_modes/mode_monitor.hpp b/system_modes/include/system_modes/mode_monitor.hpp index e23ab30..09dd727 100644 --- a/system_modes/include/system_modes/mode_monitor.hpp +++ b/system_modes/include/system_modes/mode_monitor.hpp @@ -14,8 +14,8 @@ // limitations under the License. #pragma once -#include #include +#include #include #include @@ -25,6 +25,7 @@ #include "system_modes/mode.hpp" #include "system_modes/mode_inference.hpp" +#include "system_modes/visibility_control.hpp" #include "system_modes_msgs/srv/change_mode.hpp" #include "system_modes_msgs/srv/get_mode.hpp" @@ -37,22 +38,39 @@ namespace system_modes class ModeMonitor : public rclcpp::Node { public: + SYSTEM_MODES_PUBLIC ModeMonitor(); + + SYSTEM_MODES_PUBLIC ModeMonitor(const ModeMonitor &) = delete; - std::shared_ptr inference(); + SYSTEM_MODES_PUBLIC + virtual + ~ModeMonitor(); - virtual ~ModeMonitor() = default; + SYSTEM_MODES_PUBLIC + std::shared_ptr + inference(); protected: - virtual void refresh() const; - virtual std::string header() const; - virtual std::string format_line( + SYSTEM_MODES_PUBLIC + virtual void + refresh() const; + + SYSTEM_MODES_PUBLIC + virtual std::string + header() const; + + SYSTEM_MODES_PUBLIC + virtual std::string + format_line( const std::string &, unsigned int, unsigned int, unsigned int, const std::string &, const std::string &) const; - inline const std::string MONITOR_HLINE(const std::string & label) const; + SYSTEM_MODES_LOCAL + inline const + std::string MONITOR_HLINE(const std::string & label) const; std::shared_ptr mode_inference_; std::string model_path_; @@ -60,7 +78,7 @@ class ModeMonitor : public rclcpp::Node private: rclcpp::TimerBase::SharedPtr timer_; - unsigned int rate_; + int64_t rate_; bool clear_screen_, verbose_; }; diff --git a/system_modes/include/system_modes/mode_observer.hpp b/system_modes/include/system_modes/mode_observer.hpp index dfd569d..6ec4ca1 100644 --- a/system_modes/include/system_modes/mode_observer.hpp +++ b/system_modes/include/system_modes/mode_observer.hpp @@ -52,35 +52,44 @@ using system_modes_msgs::srv::GetMode; class ModeObserver { public: + SYSTEM_MODES_PUBLIC explicit ModeObserver(std::weak_ptr); - virtual ~ModeObserver() = default; + + SYSTEM_MODES_PUBLIC + virtual + ~ModeObserver(); /** * Getter for observed state and mode. * * Returns cached observed state and mode for requested system entity (system or node). */ + SYSTEM_MODES_PUBLIC virtual StateAndMode get(const string & part_name); /** * Add part to list of observed parts. */ + SYSTEM_MODES_PUBLIC virtual void observe(const string & part_name); /** * Remove part from list of observed parts. */ + SYSTEM_MODES_PUBLIC virtual void stop_observing(const string & part_name); protected: + SYSTEM_MODES_PUBLIC virtual void transition_callback( const TransitionEvent::SharedPtr msg, const string & part_name); + SYSTEM_MODES_PUBLIC virtual void mode_event_callback( const ModeEvent::SharedPtr msg, diff --git a/system_modes/include/system_modes/visibility_control.hpp b/system_modes/include/system_modes/visibility_control.hpp new file mode 100644 index 0000000..391e8e3 --- /dev/null +++ b/system_modes/include/system_modes/visibility_control.hpp @@ -0,0 +1,54 @@ +// Copyright 2015 Open Source Robotics Foundation, Inc. +// +// 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. +#pragma once + +#ifdef __cplusplus +extern "C" +{ +#endif + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility + +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define SYSTEM_MODES_EXPORT __attribute__ ((dllexport)) + #define SYSTEM_MODES_IMPORT __attribute__ ((dllimport)) + #else + #define SYSTEM_MODES_EXPORT __declspec(dllexport) + #define SYSTEM_MODES_IMPORT __declspec(dllimport) + #endif + #ifdef SYSTEM_MODES_BUILDING_LIBRARY + #define SYSTEM_MODES_PUBLIC SYSTEM_MODES_EXPORT + #else + #define SYSTEM_MODES_PUBLIC SYSTEM_MODES_IMPORT + #endif + #define SYSTEM_MODES_PUBLIC_TYPE SYSTEM_MODES_PUBLIC + #define SYSTEM_MODES_LOCAL +#else + #define SYSTEM_MODES_EXPORT __attribute__ ((visibility("default"))) + #define SYSTEM_MODES_IMPORT + #if __GNUC__ >= 4 + #define SYSTEM_MODES_PUBLIC __attribute__ ((visibility("default"))) + #define SYSTEM_MODES_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define SYSTEM_MODES_PUBLIC + #define SYSTEM_MODES_LOCAL + #endif + #define SYSTEM_MODES_PUBLIC_TYPE +#endif + +#ifdef __cplusplus +} +#endif diff --git a/system_modes/package.xml b/system_modes/package.xml index 0ae8991..d6ab14e 100644 --- a/system_modes/package.xml +++ b/system_modes/package.xml @@ -19,10 +19,8 @@ ament_cmake - builtin_interfaces rclcpp - rclcpp_lifecycle - system_modes_msgs + rclcpp_lifecycle system_modes_msgs launch_ros @@ -38,7 +36,6 @@ launch_testing_ament_cmake launch_testing_ros ros2run - ament_cmake diff --git a/system_modes/src/mode_manager_node.cpp b/system_modes/src/mode_manager_node.cpp index 8eca50d..af355ac 100644 --- a/system_modes/src/mode_manager_node.cpp +++ b/system_modes/src/mode_manager_node.cpp @@ -49,7 +49,8 @@ using rcl_interfaces::msg::ParameterEvent; shared_ptr manager; -void transition_callback( +void +transition_callback( const TransitionEvent::SharedPtr msg, const string & node_name) { @@ -57,7 +58,8 @@ void transition_callback( manager->handle_system_deviation("transition"); } -void mode_change_callback( +void +mode_change_callback( const ModeEvent::SharedPtr msg, const string & node_name) { @@ -66,7 +68,8 @@ void mode_change_callback( manager->handle_system_deviation("mode change"); } -void transition_request_callback( +void +transition_request_callback( const TransitionEvent::SharedPtr msg, const string & node_name) { @@ -81,7 +84,8 @@ void transition_request_callback( } } -void mode_request_callback( +void +mode_request_callback( const ModeEvent::SharedPtr msg, const string & node_name) { @@ -108,7 +112,8 @@ parameter_event_callback(const ParameterEvent::SharedPtr event) manager->handle_system_deviation("parameter event"); } -int main(int argc, char * argv[]) +int +main(int argc, char * argv[]) { using namespace std::placeholders; diff --git a/system_modes/src/system_modes/mode_impl.cpp b/system_modes/src/system_modes/mode_impl.cpp index 2815118..dcc87fb 100644 --- a/system_modes/src/system_modes/mode_impl.cpp +++ b/system_modes/src/system_modes/mode_impl.cpp @@ -222,6 +222,7 @@ static const map GOAL_STATES_ = { {Transition::TRANSITION_ACTIVE_SHUTDOWN, State::PRIMARY_STATE_FINALIZED} }; +SYSTEM_MODES_PUBLIC const string state_label_(unsigned int state_id) { @@ -232,6 +233,7 @@ state_label_(unsigned int state_id) } } +SYSTEM_MODES_PUBLIC unsigned int state_id_(const string & state_label) { @@ -243,6 +245,7 @@ state_id_(const string & state_label) return 0; } +SYSTEM_MODES_PUBLIC const string transition_label_(unsigned int transition_id) { @@ -253,6 +256,7 @@ transition_label_(unsigned int transition_id) } } +SYSTEM_MODES_PUBLIC unsigned int transition_id_(const string & transition_label) { @@ -264,6 +268,7 @@ transition_id_(const string & transition_label) throw out_of_range("Unknown transition " + transition_label); } +SYSTEM_MODES_PUBLIC unsigned int goal_state_(unsigned int transition_id) { diff --git a/system_modes/src/system_modes/mode_manager.cpp b/system_modes/src/system_modes/mode_manager.cpp index cb7b2d3..b1b1b89 100644 --- a/system_modes/src/system_modes/mode_manager.cpp +++ b/system_modes/src/system_modes/mode_manager.cpp @@ -101,6 +101,10 @@ ModeManager::ModeManager() }); } +ModeManager::~ModeManager() +{ +} + std::shared_ptr ModeManager::inference() { @@ -280,7 +284,7 @@ ModeManager::on_get_state( response->current_state.id = stateAndMode.state; response->current_state.label = state_label_(stateAndMode.state); } - } catch (std::exception & ex) { + } catch (std::exception &) { response->current_state.id = State::PRIMARY_STATE_UNKNOWN; response->current_state.label = "unknown"; } @@ -341,7 +345,7 @@ ModeManager::on_get_mode( try { auto stateAndMode = this->mode_inference_->infer(node_name); response->current_mode = stateAndMode.mode; - } catch (std::exception & ex) { + } catch (std::exception &) { response->current_mode = "unknown"; } RCLCPP_INFO(this->get_logger(), " mode %s", response->current_mode.c_str()); @@ -360,7 +364,7 @@ ModeManager::on_get_available_modes( node_name.c_str()); try { response->available_modes = mode_inference_->get_available_modes(node_name); - } catch (std::exception & ex) { + } catch (std::exception &) { RCLCPP_INFO(this->get_logger(), " unknown"); } } diff --git a/system_modes/src/system_modes/mode_monitor.cpp b/system_modes/src/system_modes/mode_monitor.cpp index eb47724..cc92721 100644 --- a/system_modes/src/system_modes/mode_monitor.cpp +++ b/system_modes/src/system_modes/mode_monitor.cpp @@ -104,6 +104,10 @@ ModeMonitor::ModeMonitor() timer_ = this->create_wall_timer(std::chrono::milliseconds(rate_), [this]() {this->refresh();}); } +ModeMonitor::~ModeMonitor() +{ +} + std::shared_ptr ModeMonitor::inference() { diff --git a/system_modes/src/system_modes/mode_observer.cpp b/system_modes/src/system_modes/mode_observer.cpp index ebd9878..faece98 100644 --- a/system_modes/src/system_modes/mode_observer.cpp +++ b/system_modes/src/system_modes/mode_observer.cpp @@ -51,6 +51,10 @@ ModeObserver::ModeObserver(std::weak_ptr handle) { } +ModeObserver::~ModeObserver() +{ +} + StateAndMode ModeObserver::get(const std::string & part_name) {