Skip to content

Commit

Permalink
buildable without carma references
Browse files Browse the repository at this point in the history
  • Loading branch information
MishkaMN committed Sep 17, 2024
1 parent 6c29c35 commit a287fdc
Show file tree
Hide file tree
Showing 10 changed files with 712 additions and 901 deletions.
9 changes: 3 additions & 6 deletions subsystem_controllers/config/drivers_controller_config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -14,25 +14,22 @@
# Required subsystem controller nodes for the overall system to be functional and will have their lifecycle's managed
required_subsystem_nodes: ['']

# List of nodes which will not be directly managed by this subsystem controller
# List of nodes which will not be directly managed by this subsystem controller
# but which are required to be operational for the subsystem to function
unmanaged_required_nodes: ['']

# List of nodes in the namespace which will not be managed by this subsystem controller
# Specifically includes the lidar and gps nodes which are handled in other subsystem controllers
excluded_namespace_nodes : ['']

# List of ros1 controller drivers (node name) to consider required and who's failure shall result in automation abort
ros1_required_drivers: ['']

# List of ros1 camera drivers (node name) to consider required and who's failure shall result in automation abort.
ros1_camera_drivers: ['']

# Boolean: If this flag is true then all nodes under subsystem_namespace are treated as required in addition to any nodes in required_subsystem_nodes
full_subsystem_required: false

# Int: The time allocated for system startup in seconds
startup_duration: 30

# Double: The timeout threshold for essential drivers in ms
required_driver_timeout: 3000.0
required_driver_timeout: 3000.0
Original file line number Diff line number Diff line change
Expand Up @@ -16,89 +16,84 @@
* the License.
*/

#include <carma_planning_msgs/msg/plugin.hpp>
#include <carma_planning_msgs/srv/get_plugin_api.hpp>
#include <carma_planning_msgs/srv/plugin_list.hpp>
#include <carma_planning_msgs/srv/plugin_activation.hpp>
#include <ros2_lifecycle_manager/lifecycle_manager_interface.hpp>
#include <unordered_set>
#include <functional>
#include <vector>
#include <memory>
#include <chrono>
#include <gtest/gtest_prod.h>
#include <rmw/types.h>

#include <chrono>
#include <functional>
#include <map>
#include "entry_manager.hpp"
#include <memory>
#include <unordered_set>
#include <vector>

#include "entry.hpp"
#include "entry_manager.hpp"
#include <ros2_lifecycle_manager/lifecycle_manager_interface.hpp>

#include <carma_driver_msgs/msg/driver_status.hpp>
#include <carma_msgs/msg/system_alert.hpp>
#include <gtest/gtest_prod.h>

#include <carma_planning_msgs/msg/plugin.hpp>
#include <carma_planning_msgs/srv/get_plugin_api.hpp>
#include <carma_planning_msgs/srv/plugin_activation.hpp>
#include <carma_planning_msgs/srv/plugin_list.hpp>

namespace subsystem_controllers
{

/**
* \brief The DriverManager serves as a component to manage CARMA required ROS1 Drivers
*/
class DriverManager
{
public:

/*!
* \brief Default constructor for DriverManager with driver_timeout_ = 1000ms
*/
DriverManager();

/**
* \brief Constructor for DriverManager
*
* \param critical_driver_names The set of drivers which will be treated as required. A failure in these plugins will result in an exception
* \param camera_entries The set of camera drivers.
* \param driver_timeout The timeout threshold for essential drivers
*/
DriverManager(const std::vector<std::string>& critical_driver_names,
const std::vector<std::string>& camera_entries,
const long driver_timeout);


/*!
* \brief Update driver status
*/
void update_driver_status(const carma_driver_msgs::msg::DriverStatus::SharedPtr msg, long current_time);

/*!
* \brief Check if all critical drivers are operational
*/
std::string are_critical_drivers_operational(long current_time);

/*!
* \brief Evaluate if the sensor is available
*/
void evaluate_sensor(int &sensor_input,bool available,long current_time,long timestamp,long driver_timeout);

/*!
* \brief Handle the spin and publisher
*/
carma_msgs::msg::SystemAlert handle_spin(long time_now,long start_up_timestamp,long startup_duration);

protected:

//list of critical drivers
std::vector<std::string> critical_drivers_;

//list of camera entries
std::vector<std::string> camera_entries_;

//! Entry manager to keep track of detected plugins
std::shared_ptr<EntryManager> em_;

// timeout for critical driver timeout in milliseconds
long driver_timeout_ = 1000;

bool starting_up_ = true;

FRIEND_TEST(DriverManagerTest, testCarTruckHandleSpinFatalUnknown);

};
}
/**
* \brief The DriverManager serves as a component to manage CARMA required ROS1 Drivers
*/
class DriverManager
{
public:
/*!
* \brief Default constructor for DriverManager with driver_timeout_ = 1000ms
*/
DriverManager();

/**
* \brief Constructor for DriverManager
*
* \param critical_driver_names The set of drivers which will be treated as required. A failure in
* these plugins will result in an exception \param driver_timeout The timeout threshold for
* essential drivers
*/
DriverManager(const std::vector<std::string> & critical_driver_names, const long driver_timeout);

/*!
* \brief Update driver status
*/
void update_driver_status(
const carma_driver_msgs::msg::DriverStatus::SharedPtr msg, long current_time);

/*!
* \brief Check if all critical drivers are operational
*/
std::string are_critical_drivers_operational(long current_time);

/*!
* \brief Evaluate if the sensor is available
*/
void evaluate_sensor(
int & sensor_input, bool available, long current_time, long timestamp, long driver_timeout);

/*!
* \brief Handle the spin and publisher
*/
carma_msgs::msg::SystemAlert handle_spin(
long time_now, long start_up_timestamp, long startup_duration);

protected:
// list of critical drivers
std::vector<std::string> critical_drivers_;

//! Entry manager to keep track of detected plugins
std::shared_ptr<EntryManager> em_;

// timeout for critical driver timeout in milliseconds
long driver_timeout_ = 1000;

bool starting_up_ = true;

FRIEND_TEST(DriverManagerTest, testCarTruckHandleSpinFatalUnknown);
};
} // namespace subsystem_controllers
Original file line number Diff line number Diff line change
Expand Up @@ -21,51 +21,40 @@

namespace subsystem_controllers
{
/**
* \brief Stuct containing the algorithm configuration values for the GuidanceController
*/
struct DriversControllerConfig

/**
* \brief Stuct containing the algorithm configuration values for the GuidanceController
*/
struct DriversControllerConfig

{
//! List of ros1 controller drivers (node name) to consider required and who's failure shall
//! result in automation abort.
std::vector<std::string> ros1_required_drivers_;
//! List of nodes in the namespace which will not be managed by this subsystem controller
std::vector<std::string> excluded_namespace_nodes_;
//! The time allocated for system startup in seconds
int startup_duration_;
//! The timeout threshold for essential drivers in ms
double driver_timeout_ = 1000;

// Stream operator for this config
friend std::ostream & operator<<(std::ostream & output, const DriversControllerConfig & c)
{
//! List of ros1 controller drivers (node name) to consider required and who's failure shall result in automation abort.
std::vector<std::string> ros1_required_drivers_;
//! List of ros1 camera drivers (node name) to consider required and who's failure shall result in automation abort.
std::vector<std::string> ros1_camera_drivers_;
//! List of nodes in the namespace which will not be managed by this subsystem controller
std::vector<std::string> excluded_namespace_nodes_;
//! The time allocated for system startup in seconds
int startup_duration_;
//! The timeout threshold for essential drivers in ms
double driver_timeout_ = 1000;

output << "DriversControllerConfig { " << std::endl << "ros1_required_drivers: [ " << std::endl;

// Stream operator for this config
friend std::ostream &operator<<(std::ostream &output, const DriversControllerConfig &c)
{

output << "DriversControllerConfig { " << std::endl
<< "ros1_required_drivers: [ " << std::endl;

for (auto node : c.ros1_required_drivers_)
output << node << " ";
for (auto node : c.ros1_required_drivers_) output << node << " ";

output << "] " << std::endl << "ros1_camera_drivers: [ ";
output << "] " << std::endl << "excluded_namespace_nodes: [ ";

for (auto node : c.ros1_camera_drivers_)
output << node << " ";

output << "] " << std::endl << "excluded_namespace_nodes: [ ";
for (auto node : c.excluded_namespace_nodes_) output << node << " ";

for (auto node : c.excluded_namespace_nodes_)
output << node << " ";
output << "] " << std::endl << "startup_duration: " << c.startup_duration_ << std::endl;

output<< "] " << std::endl << "startup_duration: "<< c.startup_duration_ << std::endl;
output << "driver_timeout: " << c.driver_timeout_ << std::endl

output <<"driver_timeout: "<< c.driver_timeout_ << std::endl

<< "}" << std::endl;
return output;
}
};
<< "}" << std::endl;
return output;
}
};

} // namespace subsystem_controllers
} // namespace subsystem_controllers
Original file line number Diff line number Diff line change
Expand Up @@ -35,14 +35,14 @@ namespace subsystem_controllers
class DriversControllerNode : public BaseSubsystemController
{
public:

DriversControllerNode() = delete;

~DriversControllerNode() = default;

/**
* \brief Constructor. Set explicitly to support node composition.
*
*
* \param options The node options to use for configuring this node
*/
explicit DriversControllerNode(const rclcpp::NodeOptions &options);
Expand All @@ -62,15 +62,14 @@ namespace subsystem_controllers
// message/service callbacks
void driver_discovery_cb(const carma_driver_msgs::msg::DriverStatus::SharedPtr msg);

//! Timer callback function to check status of required ros1 drivers
//! Timer callback function to check status of required ros1 drivers
void timer_callback();

carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &prev_state);
carma_ros2_utils::CallbackReturn handle_on_activate(const rclcpp_lifecycle::State &prev_state);

//! ROS parameters
std::vector<std::string> ros1_required_drivers_;
std::vector<std::string> ros1_camera_drivers_;

// record of startup timestamp
long start_up_timestamp_;
Expand All @@ -83,4 +82,3 @@ namespace subsystem_controllers
};

} // namespace v2x_controller

Loading

0 comments on commit a287fdc

Please sign in to comment.