Skip to content

Commit 5ab1310

Browse files
committed
Updates to match with clang 19
Turns out the clang-format version bundled with vscode is 19. I was using an extension which needs it to be installed separately.
1 parent 59527c9 commit 5ab1310

File tree

5 files changed

+219
-176
lines changed

5 files changed

+219
-176
lines changed

puma_motor_driver/.clang-format

+44-53
Original file line numberDiff line numberDiff line change
@@ -1,68 +1,59 @@
11
---
22
BasedOnStyle: Google
33
AccessModifierOffset: -2
4-
ConstructorInitializerIndentWidth: 2
5-
AlignAfterOpenBracket: Align
6-
AlignConsecutiveAssignments: Consecutive
7-
AlignConsecutiveDeclarations: Consecutive
8-
AlignConsecutiveMacros: AcrossEmptyLines
9-
AlignEscapedNewlines: Left # Revisit when clang-format is updated
10-
AlignTrailingComments: true
4+
AlignConsecutiveAssignments:
5+
Enabled: true
6+
AlignCompound: true
7+
AlignConsecutiveDeclarations:
8+
Enabled: true
9+
PadOperators: true
10+
AlignConsecutiveMacros:
11+
Enabled: true
12+
AcrossEmptyLines: true
13+
PadOperators: true
14+
AlignTrailingComments:
15+
OverEmptyLines: 1
1116
AllowAllParametersOfDeclarationOnNextLine: false
17+
AllowShortFunctionsOnASingleLine: None
1218
AllowShortIfStatementsOnASingleLine: false
1319
AllowShortLoopsOnASingleLine: false
14-
AllowShortFunctionsOnASingleLine: None
15-
AlwaysBreakTemplateDeclarations: true
16-
AlwaysBreakBeforeMultilineStrings: true
20+
BinPackArguments: false
21+
BinPackParameters: false
22+
BraceWrapping:
23+
AfterCaseLabel: false
24+
AfterClass: "true"
25+
AfterControlStatement: "true"
26+
AfterEnum: "true"
27+
AfterFunction: "true"
28+
AfterNamespace: "true"
29+
AfterObjCDeclaration: false
30+
AfterStruct: "true"
31+
AfterUnion: "true"
32+
AfterExternBlock: false
33+
BeforeCatch: "true"
34+
BeforeElse: "true"
35+
BeforeLambdaBody: false
36+
BeforeWhile: false
37+
IndentBraces: "false"
38+
SplitEmptyFunction: true
39+
SplitEmptyRecord: true
40+
SplitEmptyNamespace: true
41+
BreakAfterReturnType: Automatic
1742
BreakBeforeBinaryOperators: false
43+
BreakBeforeBraces: Custom
1844
BreakBeforeTernaryOperators: false
19-
BreakConstructorInitializersBeforeComma: true
20-
BinPackArguments: false # Revisit when clang-format is updated
21-
BinPackParameters: false # Revisit when clang-format is updated
45+
BreakConstructorInitializers: BeforeComma
46+
BreakTemplateDeclarations: MultiLine
2247
ColumnLimit: 120
23-
ConstructorInitializerAllOnOneLineOrOnePerLine: true
24-
DerivePointerBinding: false
25-
PointerBindsToType: true
26-
ExperimentalAutoDetectBinPacking: false
27-
IndentCaseLabels: true
28-
MaxEmptyLinesToKeep: 1
29-
NamespaceIndentation: None
30-
ObjCSpaceBeforeProtocolList: true
48+
ConstructorInitializerIndentWidth: 2
49+
Cpp11BracedListStyle: false
50+
PackConstructorInitializers: NextLine
3151
PenaltyBreakBeforeFirstCallParameter: 19
3252
PenaltyBreakComment: 60
33-
PenaltyBreakString: 1
3453
PenaltyBreakFirstLessLess: 1000
54+
PenaltyBreakString: 1
3555
PenaltyExcessCharacter: 1000
3656
PenaltyReturnTypeOnItsOwnLine: 90
37-
SpacesBeforeTrailingComments: 2
38-
Cpp11BracedListStyle: false
39-
Standard: Auto
40-
IndentWidth: 2
41-
TabWidth: 2
42-
UseTab: Never
43-
IndentFunctionDeclarationAfterType: false
44-
SpacesInParentheses: false
45-
SpacesInAngles: false
46-
SpaceInEmptyParentheses: false
47-
SpacesInCStyleCastParentheses: false
48-
SpaceAfterControlStatementKeyword: true
49-
SpaceBeforeAssignmentOperators: true
50-
ContinuationIndentWidth: 4
5157
SortIncludes: false
52-
SpaceAfterCStyleCast: false
53-
54-
# Configure each individual brace in BraceWrapping
55-
BreakBeforeBraces: Custom
56-
57-
# Control of individual brace wrapping cases
58-
BraceWrapping:
59-
AfterClass: 'true'
60-
AfterControlStatement: 'true'
61-
AfterEnum : 'true'
62-
AfterFunction : 'true'
63-
AfterNamespace : 'true'
64-
AfterStruct : 'true'
65-
AfterUnion : 'true'
66-
BeforeCatch : 'true'
67-
BeforeElse : 'true'
68-
IndentBraces : 'false'
58+
SpacesInAngles: false
59+
TabWidth: 2

puma_motor_driver/include/puma_motor_driver/driver.hpp

+21-21
Original file line numberDiff line numberDiff line change
@@ -40,9 +40,9 @@ class Driver
4040
{
4141
public:
4242
Driver(const std::shared_ptr<clearpath_ros2_socketcan_interface::SocketCANInterface> interface,
43-
std::shared_ptr<rclcpp::Node> nh,
44-
const uint8_t& device_number,
45-
const std::string& device_name);
43+
std::shared_ptr<rclcpp::Node> nh,
44+
const uint8_t& device_number,
45+
const std::string& device_name);
4646

4747
void processMessage(const can_msgs::msg::Frame::SharedPtr received_msg);
4848

@@ -451,7 +451,7 @@ class Driver
451451
struct Field
452452
{
453453
uint8_t data[4];
454-
bool received;
454+
bool received;
455455

456456
float interpretFixed8x8()
457457
{
@@ -466,32 +466,32 @@ class Driver
466466

467467
private:
468468
std::shared_ptr<clearpath_ros2_socketcan_interface::SocketCANInterface> interface_;
469-
std::shared_ptr<rclcpp::Node> nh_;
470-
uint8_t device_number_;
471-
std::string device_name_;
469+
std::shared_ptr<rclcpp::Node> nh_;
470+
uint8_t device_number_;
471+
std::string device_name_;
472472

473-
bool configured_;
473+
bool configured_;
474474
uint8_t state_;
475475

476-
uint8_t control_mode_;
477-
double gain_p_;
478-
double gain_i_;
479-
double gain_d_;
476+
uint8_t control_mode_;
477+
double gain_p_;
478+
double gain_i_;
479+
double gain_d_;
480480
uint16_t encoder_cpr_;
481-
float gear_ratio_;
481+
float gear_ratio_;
482482

483483
/**
484484
* Helpers to generate data for CAN messages.
485485
*/
486486
can_msgs::msg::Frame::SharedPtr can_msg_;
487-
void sendId(const uint32_t id);
488-
void sendUint8(const uint32_t id, const uint8_t value);
489-
void sendUint16(const uint32_t id, const uint16_t value);
490-
void sendFixed8x8(const uint32_t id, const float value);
491-
void sendFixed16x16(const uint32_t id, const double value);
492-
can_msgs::msg::Frame getMsg(const uint32_t id);
493-
uint32_t getApi(const can_msgs::msg::Frame msg);
494-
uint32_t getDeviceNumber(const can_msgs::msg::Frame msg);
487+
void sendId(const uint32_t id);
488+
void sendUint8(const uint32_t id, const uint8_t value);
489+
void sendUint16(const uint32_t id, const uint16_t value);
490+
void sendFixed8x8(const uint32_t id, const float value);
491+
void sendFixed16x16(const uint32_t id, const double value);
492+
can_msgs::msg::Frame getMsg(const uint32_t id);
493+
uint32_t getApi(const can_msgs::msg::Frame msg);
494+
uint32_t getDeviceNumber(const can_msgs::msg::Frame msg);
495495

496496
/**
497497
* Comparing the raw bytes of the 16x16 fixed-point numbers

puma_motor_driver/include/puma_motor_driver/multi_puma_node.hpp

+17-17
Original file line numberDiff line numberDiff line change
@@ -118,32 +118,32 @@ class MultiPumaNode : public rclcpp::Node
118118

119119
private:
120120
std::shared_ptr<clearpath_ros2_socketcan_interface::SocketCANInterface> interface_;
121-
std::vector<puma_motor_driver::Driver> drivers_;
122-
123-
bool active_;
124-
double gear_ratio_;
125-
int encoder_cpr_;
126-
int freq_;
127-
uint8_t status_count_;
128-
uint8_t desired_mode_;
129-
std::string canbus_dev_;
121+
std::vector<puma_motor_driver::Driver> drivers_;
122+
123+
bool active_;
124+
double gear_ratio_;
125+
int encoder_cpr_;
126+
int freq_;
127+
uint8_t status_count_;
128+
uint8_t desired_mode_;
129+
std::string canbus_dev_;
130130
std::vector<std::string> joint_names_;
131-
std::vector<int64_t> joint_can_ids_;
132-
std::vector<int64_t> joint_directions_;
131+
std::vector<int64_t> joint_can_ids_;
132+
std::vector<int64_t> joint_directions_;
133133

134-
can_msgs::msg::Frame::SharedPtr recv_msg_;
135-
clearpath_motor_msgs::msg::PumaMultiStatus status_msg_;
134+
can_msgs::msg::Frame::SharedPtr recv_msg_;
135+
clearpath_motor_msgs::msg::PumaMultiStatus status_msg_;
136136
clearpath_motor_msgs::msg::PumaMultiFeedback feedback_msg_;
137137

138138
double gain_p_;
139139
double gain_i_;
140140
double gain_d_;
141141

142-
rclcpp::Node::SharedPtr node_handle_;
143-
rclcpp::Publisher<clearpath_motor_msgs::msg::PumaMultiStatus>::SharedPtr status_pub_;
142+
rclcpp::Node::SharedPtr node_handle_;
143+
rclcpp::Publisher<clearpath_motor_msgs::msg::PumaMultiStatus>::SharedPtr status_pub_;
144144
rclcpp::Publisher<clearpath_motor_msgs::msg::PumaMultiFeedback>::SharedPtr feedback_pub_;
145-
rclcpp::Subscription<sensor_msgs::msg::JointState>::SharedPtr cmd_sub_;
146-
rclcpp::TimerBase::SharedPtr run_timer_;
145+
rclcpp::Subscription<sensor_msgs::msg::JointState>::SharedPtr cmd_sub_;
146+
rclcpp::TimerBase::SharedPtr run_timer_;
147147
};
148148

149149
#endif // PUMA_MOTOR_DRIVER_PUMA_NODE_H

0 commit comments

Comments
 (0)