forked from autowarefoundation/autoware_vision_pilot
-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathcan_interface.hpp
More file actions
89 lines (68 loc) · 2.29 KB
/
can_interface.hpp
File metadata and controls
89 lines (68 loc) · 2.29 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
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_