Skip to content

Commit b5e643c

Browse files
Fix code style issues with clang_format
1 parent cc6bed8 commit b5e643c

File tree

5 files changed

+557
-475
lines changed

5 files changed

+557
-475
lines changed

autonomy/interfacing/can/include/can_core.hpp

Lines changed: 39 additions & 40 deletions
Original file line numberDiff line numberDiff line change
@@ -2,60 +2,59 @@
22
#define CAN_CORE_HPP
33

44
#include "rclcpp/rclcpp.hpp"
5+
#include <cstdint>
56
#include <string>
67
#include <vector>
7-
#include <cstdint>
88

9-
namespace autonomy
10-
{
9+
namespace autonomy {
1110

1211
struct CanMessage {
13-
uint32_t id; // CAN message ID
14-
std::vector<uint8_t> data; // Message data (up to 8 bytes for classic CAN)
15-
uint8_t dlc; // Data Length Code
16-
bool is_extended_id; // Extended frame format flag
17-
bool is_remote_frame; // Remote transmission request flag
18-
uint64_t timestamp_us; // Timestamp in microseconds
12+
uint32_t id; // CAN message ID
13+
std::vector<uint8_t> data; // Message data (up to 8 bytes for classic CAN)
14+
uint8_t dlc; // Data Length Code
15+
bool is_extended_id; // Extended frame format flag
16+
bool is_remote_frame; // Remote transmission request flag
17+
uint64_t timestamp_us; // Timestamp in microseconds
1918
};
2019

2120
struct CanConfig {
22-
std::string interface_name; // CAN interface name (e.g., "can0")
23-
std::string device_path; // Device path for SLCAN (e.g., "/dev/ttyACM0")
24-
std::string bustype; // Bus type: "socketcan" or "slcan"
25-
uint32_t bitrate; // Bitrate in bps for arbitration phase
26-
uint32_t data_bitrate; // Data bitrate in bps for CAN-FD data phase
27-
uint32_t receive_timeout_ms; // Receive timeout in milliseconds
21+
std::string interface_name; // CAN interface name (e.g., "can0")
22+
std::string device_path; // Device path for SLCAN (e.g., "/dev/ttyACM0")
23+
std::string bustype; // Bus type: "socketcan" or "slcan"
24+
uint32_t bitrate; // Bitrate in bps for arbitration phase
25+
uint32_t data_bitrate; // Data bitrate in bps for CAN-FD data phase
26+
uint32_t receive_timeout_ms; // Receive timeout in milliseconds
2827
};
2928

3029
class CanCore {
3130
public:
32-
CanCore(const rclcpp::Logger& logger);
33-
34-
// CAN Interface Management
35-
bool initialize(const CanConfig& config);
36-
bool shutdown();
37-
bool isInitialized() const;
38-
39-
// Message Transmission
40-
bool sendMessage(const CanMessage& message);
41-
42-
// Message Reception
43-
bool receiveMessage(CanMessage& message);
44-
31+
CanCore(const rclcpp::Logger &logger);
32+
33+
// CAN Interface Management
34+
bool initialize(const CanConfig &config);
35+
bool shutdown();
36+
bool isInitialized() const;
37+
38+
// Message Transmission
39+
bool sendMessage(const CanMessage &message);
40+
41+
// Message Reception
42+
bool receiveMessage(CanMessage &message);
43+
4544
private:
46-
rclcpp::Logger logger_;
47-
48-
// Internal state
49-
int socket_fd_;
50-
bool initialized_;
51-
bool connected_;
52-
CanConfig config_;
53-
54-
// Internal helper methods
55-
bool setupSocketCan();
56-
bool setupSlcan();
45+
rclcpp::Logger logger_;
46+
47+
// Internal state
48+
int socket_fd_;
49+
bool initialized_;
50+
bool connected_;
51+
CanConfig config_;
52+
53+
// Internal helper methods
54+
bool setupSocketCan();
55+
bool setupSlcan();
5756
};
5857

59-
}
58+
} // namespace autonomy
6059

6160
#endif // CAN_CORE_HPP
Lines changed: 16 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -1,16 +1,16 @@
11
#ifndef CAN_NODE_HPP
22
#define CAN_NODE_HPP
33

4-
#include "rclcpp/rclcpp.hpp"
4+
#include "can_core.hpp"
55
#include "rclcpp/generic_subscription.hpp"
6+
#include "rclcpp/rclcpp.hpp"
67
#include "std_msgs/msg/string.hpp"
7-
#include "can_core.hpp"
8-
#include <vector>
9-
#include <string>
108
#include <memory>
9+
#include <string>
10+
#include <vector>
1111

1212
struct TopicConfig {
13-
// name of the topic, and the message type
13+
// name of the topic, and the message type
1414
std::string name;
1515
std::string type;
1616
};
@@ -23,18 +23,23 @@ class CanNode : public rclcpp::Node {
2323
autonomy::CanCore can_;
2424
std::vector<TopicConfig> topic_configs_;
2525
std::vector<std::shared_ptr<rclcpp::GenericSubscription>> subscribers_;
26-
rclcpp::TimerBase::SharedPtr receive_timer_; // Timer to periodically check for CAN messages
27-
26+
rclcpp::TimerBase::SharedPtr
27+
receive_timer_; // Timer to periodically check for CAN messages
28+
2829
// Methods
2930
void loadTopicConfigurations();
3031
void createSubscribers();
31-
std::string discoverTopicType(const std::string& topic_name);
32-
void topicCallback(std::shared_ptr<rclcpp::SerializedMessage> msg, const std::string& topic_name, const std::string& topic_type);
32+
std::string discoverTopicType(const std::string &topic_name);
33+
void topicCallback(std::shared_ptr<rclcpp::SerializedMessage> msg,
34+
const std::string &topic_name,
35+
const std::string &topic_type);
3336
void receiveCanMessages(); // Method to be called by the timer
3437

3538
// Helper methods
36-
uint32_t generateCanId(const std::string& topic_name);
37-
std::vector<autonomy::CanMessage> createCanMessages(const std::string& topic_name, std::shared_ptr<rclcpp::SerializedMessage> ros_msg);
39+
uint32_t generateCanId(const std::string &topic_name);
40+
std::vector<autonomy::CanMessage>
41+
createCanMessages(const std::string &topic_name,
42+
std::shared_ptr<rclcpp::SerializedMessage> ros_msg);
3843
};
3944

4045
#endif // CAN_NODE_HPP

0 commit comments

Comments
 (0)