Skip to content
This repository has been archived by the owner on Feb 9, 2023. It is now read-only.

Conditonal Compilation: Compile without CAN #84

Open
wants to merge 5 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
15 changes: 10 additions & 5 deletions src/subsystem/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,8 +1,13 @@
add_subdirectory(can)
add_executable(subsystem subsystem.cpp drive_controller.hpp drive_controller.cpp)
add_subdirectory(task_scheduler)

find_package(Boost COMPONENTS system REQUIRED)
target_include_directories(subsystem PUBLIC ${Boost_INCLUDE_DIR} rover_can rover_system_messages)
target_link_libraries(subsystem PUBLIC network rover_can rover_system_messages Boost::system)
find_package(Boost COMPONENTS system)
if (Boost_FOUND AND Boost_system_FOUND)
add_executable(subsystem subsystem.cpp drive_controller.hpp drive_controller.cpp)
target_include_directories(subsystem PUBLIC ${Boost_INCLUDE_DIR} rover_can rover_system_messages)
target_link_libraries(subsystem PUBLIC network rover_can rover_system_messages Boost::system)

target_compile_features(subsystem PRIVATE cxx_std_17)
target_compile_features(subsystem PRIVATE cxx_std_17)
else()
message(STATUS "rover_subsystem: excluded from build since Boost is missing")
endif()
25 changes: 13 additions & 12 deletions src/subsystem/can/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,22 +1,23 @@
add_library(rover_can rover_can.hpp constants.hpp commands.hpp commands.cpp)

target_include_directories(rover_can PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
target_compile_features(rover_can PRIVATE cxx_std_20)

# If ONBOARD_CAN_BUS has been manually defined (or is cached), then don't override it with auto-detection
if (NOT DEFINED ONBOARD_CAN_BUS)
# If ROVER_CAN_AVAIL has been manually defined (or is cached), then don't override it with auto-detection
if (NOT DEFINED ROVER_CAN_AVAIL)
if (${CMAKE_SYSTEM_NAME} STREQUAL "Linux")
set(ONBOARD_CAN_BUS ON CACHE BOOL "Compile subsystem with Linux CAN bus libraries")
set(ROVER_CAN_AVAIL ON CACHE BOOL "Compile subsystem with Linux CAN bus libraries")
message(STATUS "rover_can: Platform supports full CAN functionality")
else()
set(ONBOARD_CAN_BUS OFF CACHE BOOL "Compile subsystem with Linux CAN bus libraries")
set(ROVER_CAN_AVAIL OFF CACHE BOOL "Compile subsystem with Linux CAN bus libraries")
message(STATUS "rover_can: Platform does not support rover CAN bus")
endif()
endif()

if (ONBOARD_CAN_BUS)
target_compile_definitions(rover_can PUBLIC ONBOARD_CAN_BUS)
message(STATUS "rover_can: Building in ONBOARD mode")
add_library(rover_can rover_can.hpp constants.hpp commands.hpp commands.cpp)

target_include_directories(rover_can PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
target_compile_features(rover_can PRIVATE cxx_std_20)

if (ROVER_CAN_AVAIL)
target_compile_definitions(rover_can PUBLIC ROVER_CAN_AVAIL)
message(STATUS "rover_can: Building with full CAN bus support")
else()
message(STATUS "rover_can: Building in OFFLINE mode. CAN bus is disabled")
message(STATUS "rover_can: Building in placeholder/OFFLINE mode. CAN bus is disabled")
endif()
40 changes: 28 additions & 12 deletions src/subsystem/can/commands.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,14 @@
#include "commands.hpp"

#ifdef ROVER_CAN_AVAIL
#include <unistd.h>
#include <net/if.h>
#include <sys/ioctl.h>
#include <sys/socket.h>
#include <linux/can.h>
#include <linux/can/raw.h>
#endif

//Can socket number
static int can_socket = 0;
static bool socket_open = false;
Expand Down Expand Up @@ -29,7 +38,7 @@ int can_send(Node device, Command command, int num_bytes, unsigned int data) {
//Set status to unset
status = CAN_Status::UNSET;

#ifdef ONBOARD_CAN_BUS
#ifdef ROVER_CAN_AVAIL
//Socket is not open, nothing can send
if (!socket_open) { return 1; }

Expand All @@ -47,7 +56,7 @@ int can_send(Node device, Command command, int num_bytes, unsigned int data) {
status = CAN_Status::FAILED_WRITE;
return 1;
}
#endif
#endif
//Successfully sent
status = CAN_Status::SUCCESS;
return 0;
Expand All @@ -58,7 +67,7 @@ int can_request(Node device, Command command, float f) {
//Set status to unset
status = CAN_Status::UNSET;

#ifdef ONBOARD_CAN_BUS
#ifdef ROVER_CAN_AVAIL
//Socket is not open, nothing can send
if (!socket_open) { return 1; }

Expand All @@ -71,26 +80,28 @@ int can_request(Node device, Command command, float f) {
status = CAN_Status::FAILED_REQUEST;
return 1;
}
#endif
#endif
//Successfully sent
status = CAN_Status::SUCCESS;
return 0;
}

void can_read_all(const std::function<void(can_frame*)>& callback) {
#ifdef ROVER_CAN_AVAIL
if (socket_open) {
can_frame received_frame;

while (read(can_socket, &received_frame, sizeof(can_frame)) > 0) {
callback(&received_frame);
}
}
#endif
}

uint64_t canframe_get_u64(can_frame* frame) {
uint64_t x = 0;
for (int i = 0; i < 8; i++) {
x |= ((uint64_t)(frame->data[i]) << (8 * (-i + 7)));
x |= ((uint64_t)(can_frame_get_data(frame)[i]) << (8 * (-i + 7)));
}
return x;
}
Expand Down Expand Up @@ -143,9 +154,10 @@ void parse_environmental_analysis_information(EAInformation& write_to, uint64_t
write_to.humidity = (float((0x00000000FF000000l & p) >> 24)) / 10.0f;
}

#ifdef ONBOARD_CAN_BUS
// Exclude these internal functions entirely if CAN isn't available
#ifdef ROVER_CAN_AVAIL
//Create a can frame
can_frame get_can_frame(int modifier, Node device, Command command, int num_bytes, unsigned int data) {
static can_frame get_can_frame(int modifier, Node device, Command command, int num_bytes, unsigned int data) {
can_frame frame;
frame.can_id = command | (device << 5) | (modifier << 8);
frame.can_dlc = num_bytes;
Expand All @@ -162,7 +174,7 @@ can_frame get_can_frame(int modifier, Node device, Command command, int num_byte
}

//Create a frame for receiving
can_frame get_can_request_frame(int modifier, Node device, Command command, float f) {
static can_frame get_can_request_frame(int modifier, Node device, Command command, float f) {
can_frame frame;
frame.can_id = (0x40000000) | command | (device << 5) | (modifier << 8);
frame.can_dlc = 0;
Expand All @@ -187,7 +199,7 @@ unsigned int get_big_endian(unsigned int u) {

//Open can socket
bool can_open_socket() {
#ifdef ONBOARD_CAN_BUS
#ifdef ROVER_CAN_AVAIL
//Get socket number
can_socket = socket(PF_CAN, SOCK_RAW, CAN_RAW);
if (can_socket < 0) { return false; }
Expand Down Expand Up @@ -218,17 +230,21 @@ bool can_open_socket() {

//Disable receive filter, then open socket
if (bind(can_socket, (struct sockaddr *)&addr, sizeof(addr)) < 0) { return false; }
#endif
//Socket has been successfully opened
socket_open = true;
return true;

#else
return false;
#endif
}

//Close can socket
void can_close_socket() {
#ifdef ONBOARD_CAN_BUS

#ifdef ROVER_CAN_AVAIL
close(can_socket);
#endif
#endif
socket_open = false;
}

Expand Down
61 changes: 37 additions & 24 deletions src/subsystem/can/commands.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,29 +3,19 @@
#include <cstring>
#include <chrono>
#include <functional>
#include <fcntl.h>

#ifdef ONBOARD_CAN_BUS
#include <unistd.h>
#include <net/if.h>
#include <sys/ioctl.h>
#include <sys/socket.h>

#include <linux/can.h>
#include <linux/can/raw.h>
#else

#warning Compiling rover_can in offline mode

// Declare that can_frame exists so offline devices can still compile
extern "C" {
struct can_frame;
}
#include "constants.hpp"

#ifdef ROVER_CAN_AVAIL
#include <linux/can.h>
#else
// Declare that can_frame exists so offline devices can still compile
extern "C" {
struct can_frame;
}
#endif

#include "constants.hpp"

//Overloads for can_send
int can_send(Node device, Command command, unsigned int data);
int can_send(Node device, Command command, int data);
Expand All @@ -44,6 +34,35 @@ constexpr int can_id(Node device, Command command) {
return command | (device << 5);
}

/// Return the can_id from a can_frame pointer.
///
/// This function allows programs that use rover_can to compile even if
/// Linux/CAN isn't available. However, programs should try to avoid calling
/// these functions if CAN isn't available since the return value does not
/// make sense.
inline uint32_t can_frame_get_can_id(const can_frame* frame) {
#ifdef ROVER_CAN_AVAIL
return frame->can_id;
#else
return 0;
#endif
}

/// Return the data pointer from a can_frame pointer.
///
/// This function allows programs that use rover_can to compile even if
/// Linux/CAN isn't available. This function returns null if CAN is not
/// available, so users should ensure this function is not called if CAN did not
/// initialize successfully.
inline uint8_t* can_frame_get_data(const can_frame* frame) {
#ifdef ROVER_CAN_AVAIL
return frame->data;
#else
// Returning null is okay since these functions should never be called if CAN isn't available
return nullptr;
#endif
}

uint64_t canframe_get_u64(can_frame* frame);

void parse_control_information(ControlInformation& write_to, uint64_t p1, uint64_t p2);
Expand All @@ -53,12 +72,6 @@ void parse_arm_information(ArmInformation& write_to, uint64_t p);
void parse_gripper_information(GripperInformation& write_to, uint64_t p);
void parse_environmental_analysis_information(EAInformation& write_to, uint64_t p);

#ifdef ONBOARD_CAN_BUS
//Create a can frame
can_frame get_can_frame(int modifier, Node device, Command command, int num_bytes, unsigned int data);
can_frame get_can_request_frame(int modifier, Node device, Command command, float f);
#endif

//Converts unsigned int to big endian
unsigned int get_big_endian(unsigned int u);

Expand Down
4 changes: 2 additions & 2 deletions src/subsystem/subsystem.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -140,7 +140,7 @@ int main() {
}

can_read_all([] (can_frame* frame) {
switch (frame->can_id) {
switch (can_frame_get_can_id(frame)) {
case can_id(Node::CONTROL_TEENSY, Command::TEENSY_DATA_PACKET_1):
parse_control_p1(rover_sensor_information, canframe_get_u64(frame));
break;
Expand All @@ -150,7 +150,7 @@ int main() {
case can_id(Node::DRIVE_AXIS_0, Command::GET_VBUS_VOLTAGE):
unsigned int v = 0;
for (int i = 0; i < 4; i++) {
v |= ((unsigned int)frame->data[i] << (8 * i));
v |= (static_cast<uint32_t>(can_frame_get_data(frame)[i]) << (8 * i));
}
union { unsigned int ul; float fl; } conv = { .ul = v };
rover_sensor_information.ps_batt = conv.fl;
Expand Down
3 changes: 3 additions & 0 deletions src/subsystem/task_scheduler/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
add_library(task_scheduler task_scheduler.hpp task_scheduler.cpp)
target_include_directories(task_scheduler PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
target_compile_features(task_scheduler PUBLIC cxx_std_14)
80 changes: 80 additions & 0 deletions src/subsystem/task_scheduler/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,80 @@
# Task Scheduler Manual
## Overview
The task scheduler is for running multiple tasks in the same thread in a controlled and predictable manner. Simply put, with this task scheduler, functions can schedule a time to be called again. When no functions are ready to dispatch, the program can sleep instead of busy wait.

Tasks are vaguely inspired by FreeRTOS Tasks and Boost.Fiber but are much, much simpler. A task is only a function callback that may be dispatched synchronously when calling `TaskScheduler::poll()`.

## Problems Addressed

Formerly, the Main Event Loop in the subsystem computer checked for work by polling. A polling-style loop basically looks like:
1. Check if any network packets have arrived
2. Check if the drive controller should update the motors
3. Check if a CAN heartbeat should be sent
4. Check if a system status update should be sent
5. Repeat (no delay)

On most iterations, this program does no work: it wastes nearly 100% of its CPU time *checking* for work. This method scales poorly. On small microcontrollers, busy-waiting is standard. On Raspberry Pi, spinning hogs valuable CPU time and reduces the system's overall capacity. Busy-waiting on a PC also wastes a ton of electricity.

## Usage
### Including
Link to the CMake target `task_scheduler`. The target has no dependencies other than the C++ STL.

In source files, include the header `task_scheduler.hpp`
### Code
Create a `TaskScheduler()` to manage tasks.

For each task, create a `Task(const std::function<void(Task&)>& callback)` for desired tasks. The `Task&` is a reference to the task itself. Providing a null callback and then scheduling the task will result in undefined behavior.
```C++
// Prints "Fizz" every 3 seconds
Task fizz([] (Task& self) {
// Tasks must reschedule themselves
self.set_next_occurrence(std::chrono::steady_clock::now() + std::chrono::seconds(3));
std::cout << "Fizz\n";
}));
```
After creating the task, add it to the scheduler with `TaskScheduler::add_task(Task&)`.
```C++
sched.add_task(fizz);
```
Tasks must be allocated as long as they are scheduled. If a scheduled task is destructed, it will be canceled safely and automatically.

To dispatch all tasks which are ready, call `TaskScheduler::poll()`. This can be combined with `TaskScheduler::get_next_dispatch_time()` to sleep during inactivity.
```C++
while (!sched.empty()) {
std::this_thread::sleep_until(sched.get_next_dispatch_time());
sched.poll();
}
```
#### Complete Example
```C++
#include <task_scheduler.hpp>
#include <iostream>
#include <thread>

TaskScheduler sched;

void print_buzz_forever(Task& self) {
self.set_next_occurrence(std::chrono::steady_clock::now() + std::chrono::seconds(5));
std::cout << "Buzz\n";
}

int main() {
// Prints "Fizz" every 3 seconds
Task fizz([] (Task& self) {
// Tasks must reschedule themselves
self.set_next_occurrence(std::chrono::steady_clock::now() + std::chrono::seconds(3));
std::cout << "Fizz\n";
}));
sched.add_task(fizz);

// Another way to add a task by binding a function
Task buzz_task(print_buzz_forever);
sched.add_task(buzz_task);

while (!sched.empty()) {
std::this_thread::sleep_until(sched.get_next_dispatch_time());
sched.poll();
}
return 0;
}
```
Loading