# Coding Style of Electrical System
###### tags: `tutorial` `electrical_system` `NTURT`
##### Author: @QuantumSpawner
## Why emphasizing coding style
Every organization has their own coding style for consistancy, and NTURT is no exception. We hope you to follow (yes, it's not necessary) as you may have to code in such manner at NTURT in the future.
## Format
Please checkout:
- [Coding Style](/KXP8UcBPT4umylMUGAoSQA) for coding style guide of NTURT.
- [Documentation Format](/qh3LSmI9TQC1OI_7pyxDFQ) for writting documentation for code.
## Example
You may refer to our [github page](https://github.com/NTURacingTeam) for the coding style.
### Example: LED controller
Header file: [nturt_led_controller/include/nturt_led_controller/led_controller.hpp](https://github.com/NTURacingTeam/nturt_led_controller/blob/ros2/include/nturt_led_controller/led_controller.hpp)
```cpp=
/**
* @file nturt_led_controller.hpp
* @author QuantumSpawner jet22854111@gmail.com
* @brief ROS2 package for controlling leds connected to rpi that indicate the
* state of ros2.
*/
#ifndef LED_CONTROLLER_HPP
#define LED_CONTROLLER_HPP
// std include
#include <memory>
// gpio include
#include <wiringPi.h>
// ros2 include
#include <rclcpp/rclcpp.hpp>
// ros2 message include
#include <can_msgs/msg/frame.hpp>
#include <rcl_interfaces/msg/log.hpp>
// nturt include
#include "nturt_led_controller/project_def.hpp"
/**
* @author QuantumSpawner jet22854111@gmail.com
* @brief Class for controlling leds connected to rpi that indicate the state of
* ros2.
*/
class LedController : public rclcpp::Node {
public:
/// @brief Constructor of led_controller.
LedController(rclcpp::NodeOptions _options);
private:
/// @brief ROS2 sbscriber to "/from_can_bus", for receiving can signal.
rclcpp::Subscription<can_msgs::msg::Frame>::SharedPtr can_sub_;
/// @brief ROS2 subscriber to "/rosout". for receiving error messages from
/// other nodes.
rclcpp::Subscription<rcl_interfaces::msg::Log>::SharedPtr rosout_sub_;
/// @brief ROS2 timer for determining if ros is alive.
rclcpp::TimerBase::SharedPtr led_timer_;
// internal state
/// @brief If ros led is on.
bool ros_led_on_ = false;
/// @brief Callback function when ros is about to shutdown.
void onShutdown();
/// @brief Callback function when receiving message from "/from_can_bus".
void onCan(const std::shared_ptr<can_msgs::msg::Frame> _msg);
/// @brief Callback function when receiving message from "/rosout".
void onRosout(const std::shared_ptr<rcl_interfaces::msg::Log> _msg);
/// @brief Timed callback function called for blinking ros led on and off.
void led_callback();
};
#endif // LED_CONTROLLER_HPP
```
Source file: [nturt_led_controller/src/led_controller.cpp](https://github.com/NTURacingTeam/nturt_led_controller/blob/ros2/src/led_controller.cpp)
```cpp=
#include "nturt_led_controller/led_controller.hpp"
// std include
#include <chrono>
#include <functional>
#include <memory>
// gpio include
#include <wiringPi.h>
// nturt include
#include "nturt_led_controller/project_def.hpp"
using namespace std::chrono_literals;
LedController::LedController(rclcpp::NodeOptions _options)
: Node("nturt_led_controller_node", _options),
can_sub_(this->create_subscription<can_msgs::msg::Frame>(
"/from_can_bus", 10,
std::bind(&LedController::onCan, this, std::placeholders::_1))),
rosout_sub_(this->create_subscription<rcl_interfaces::msg::Log>(
"/rosout", 10,
std::bind(&LedController::onRosout, this, std::placeholders::_1))),
led_timer_(this->create_wall_timer(
1s, std::bind(&LedController::led_callback, this))) {
// register onShutdown to ros
rclcpp::on_shutdown(std::bind(&LedController::onShutdown, this));
// initiate wiringpi gpio
wiringPiSetup();
pinMode(LED_ROS_PIN, OUTPUT);
pinMode(LED_CAN_PIN, OUTPUT);
pinMode(LED_WARN_PIN, OUTPUT);
pinMode(LED_ERROR_PIN, OUTPUT);
pinMode(LED_RESERVED_PIN, OUTPUT);
}
void LedController::onShutdown() {
digitalWrite(LED_ROS_PIN, LOW);
digitalWrite(LED_CAN_PIN, LOW);
digitalWrite(LED_WARN_PIN, LOW);
digitalWrite(LED_ERROR_PIN, LOW);
digitalWrite(LED_RESERVED_PIN, LOW);
}
void LedController::onCan(const std::shared_ptr<can_msgs::msg::Frame> _msg) {
(void)_msg;
digitalWrite(LED_CAN_PIN, HIGH);
rclcpp::sleep_for(1ms);
digitalWrite(LED_CAN_PIN, LOW);
}
void LedController::onRosout(
const std::shared_ptr<rcl_interfaces::msg::Log> _msg) {
// warn level = 30
if (_msg->level == 30) {
digitalWrite(LED_WARN_PIN, HIGH);
rclcpp::sleep_for(100ms);
digitalWrite(LED_WARN_PIN, LOW);
}
// error level = 40, fatal level = 50
else if (_msg->level == 40 || _msg->level == 50) {
digitalWrite(LED_ERROR_PIN, HIGH);
rclcpp::sleep_for(100ms);
digitalWrite(LED_ERROR_PIN, LOW);
}
}
void LedController::led_callback() {
if (!ros_led_on_) {
digitalWrite(LED_ROS_PIN, HIGH);
ros_led_on_ = true;
} else {
digitalWrite(LED_ROS_PIN, LOW);
ros_led_on_ = false;
}
}
#include "rclcpp_components/register_node_macro.hpp"
RCLCPP_COMPONENTS_REGISTER_NODE(LedController)
```