Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
31 commits
Select commit Hold shift + click to select a range
347ba57
init can interface header
TranHuuNhatHuy Dec 14, 2025
b27bc80
define libs in header
TranHuuNhatHuy Dec 14, 2025
8fbcc40
define can state ids struct
TranHuuNhatHuy Dec 14, 2025
4571094
define can inference class
TranHuuNhatHuy Dec 14, 2025
d4b6708
add update states
TranHuuNhatHuy Dec 14, 2025
a9cf037
get latest decoded can state
TranHuuNhatHuy Dec 14, 2025
03f13e4
add replay mode confirmation
TranHuuNhatHuy Dec 14, 2025
c672306
init private props
TranHuuNhatHuy Dec 14, 2025
5aab8d3
add real time inference states
TranHuuNhatHuy Dec 14, 2025
4513973
add file replay states
TranHuuNhatHuy Dec 14, 2025
6bae06f
declaring decoding CAN IDs
TranHuuNhatHuy Dec 14, 2025
32add7b
add func to parse frames
TranHuuNhatHuy Dec 14, 2025
1919ebb
add func to decode speed from CAN
TranHuuNhatHuy Dec 14, 2025
565c7c8
add func to decode steering angle from CAN
TranHuuNhatHuy Dec 14, 2025
cb8981b
wrapping up header
TranHuuNhatHuy Dec 14, 2025
b084e92
init can_interface.cpp
TranHuuNhatHuy Dec 14, 2025
792c69c
basic libs
TranHuuNhatHuy Dec 14, 2025
ac48e61
linux SocketCAN headers
TranHuuNhatHuy Dec 14, 2025
b6b2ade
add can interface initialization with some cool ass loggings
TranHuuNhatHuy Dec 14, 2025
b60457d
add class destructor for can inf
TranHuuNhatHuy Dec 14, 2025
096c759
main update loop
TranHuuNhatHuy Dec 14, 2025
619229d
get latest vehicle state
TranHuuNhatHuy Dec 14, 2025
7ca793c
decoding logic
TranHuuNhatHuy Dec 14, 2025
d825c5a
decode speed
TranHuuNhatHuy Dec 14, 2025
c1259cf
decode steering angle
TranHuuNhatHuy Dec 14, 2025
e8a66b4
setup socket
TranHuuNhatHuy Dec 14, 2025
1624f3d
read socket logic
TranHuuNhatHuy Dec 14, 2025
59a00a7
setup file if file replay
TranHuuNhatHuy Dec 14, 2025
cd37f52
init read file line logic, assuming update is called properly so a st…
TranHuuNhatHuy Dec 14, 2025
010d7bb
finalize read file line
TranHuuNhatHuy Dec 14, 2025
7a80c00
wrapping up the script
TranHuuNhatHuy Dec 14, 2025
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
Original file line number Diff line number Diff line change
@@ -0,0 +1,89 @@
#ifndef AUTOWARE_POV_DRIVERS_CAN_INTERFACE_HPP_
#define AUTOWARE_POV_DRIVERS_CAN_INTERFACE_HPP_

#include <string>
#include <optional>
#include <fstream>
#include <vector>
#include <cmath>
#include <limits>
#include <chrono>

namespace autoware_pov::drivers {

struct CanVehicleState {
double speed_kmph = std::numeric_limits<double>::quiet_NaN(); // Speed, CAN ID 0xA1
double steering_angle_deg = std::numeric_limits<double>::quiet_NaN(); // Steering, CAN ID 0xA4
bool is_valid = false;
};

/**
* @brief CAN Interface for hardware (SocketCAN) and file replay (.asc)
* - If interface_name ends with ".asc" : file replay.
* - Otherwise : open a SocketCAN interface (real-time inference).
*/
class CanInterface {

public:

/**
* @brief Constructor
* @param interface_name "can0", "vcan0", or path to .asc file (e.g. "./assets/test.asc")
*/
explicit CanInterface(const std::string& interface_name);

~CanInterface();

/**
* @brief Read available CAN frames and update state
* * Call this once per cycle in main loop.
* In real-time inference : reads all frames currently in the socket buffer.
* In fie replay : reads the next line from the ASC file.
* * @return true if new data was processed, false otherwise
*/
bool update();

/**
* @brief Get latest decoded vehicle state
*/
CanVehicleState getState() const;

/**
* @brief Check if in file replay
*/
bool isReplayMode() const { return is_file_mode_; }

private:

// State
CanVehicleState current_state_;
bool is_file_mode_ = false;

// Real-time inference (SocketCAN)
int socket_fd_ = -1;
void setupSocket(const std::string& iface_name);
bool readSocket();

// File replay (.asc)
std::ifstream file_stream_;
void setupFile(const std::string& file_path);
bool readFileLine();

// Decoding IDs
static constexpr int ID_SPEED = 0xA1; // Or A1, 161
static constexpr int ID_STEERING = 0xA4; // Or A4, 164

void parseFrame(
int can_id,
const std::vector<uint8_t>& data
);

double decodeSpeed(const std::vector<uint8_t>& data);

double decodeSteering(const std::vector<uint8_t>& data);

};

} // namespace autoware_pov::drivers

#endif // AUTOWARE_POV_DRIVERS_CAN_INTERFACE_HPP_
Loading
Loading