Start using clang-format
This commit is contained in:
parent
24a7c07695
commit
7ff1708ce1
121
.clang-format
Normal file
121
.clang-format
Normal file
@ -0,0 +1,121 @@
|
|||||||
|
---
|
||||||
|
Language: Cpp
|
||||||
|
# BasedOnStyle: LLVM
|
||||||
|
AccessModifierOffset: -2
|
||||||
|
AlignAfterOpenBracket: Align
|
||||||
|
AlignConsecutiveAssignments: false
|
||||||
|
AlignConsecutiveDeclarations: false
|
||||||
|
AlignEscapedNewlines: Right
|
||||||
|
AlignOperands: true
|
||||||
|
AlignTrailingComments: true
|
||||||
|
AllowAllParametersOfDeclarationOnNextLine: true
|
||||||
|
AllowShortBlocksOnASingleLine: false
|
||||||
|
AllowShortCaseLabelsOnASingleLine: false
|
||||||
|
AllowShortFunctionsOnASingleLine: All
|
||||||
|
AllowShortIfStatementsOnASingleLine: false
|
||||||
|
AllowShortLoopsOnASingleLine: false
|
||||||
|
AlwaysBreakAfterDefinitionReturnType: None
|
||||||
|
AlwaysBreakAfterReturnType: None
|
||||||
|
AlwaysBreakBeforeMultilineStrings: false
|
||||||
|
AlwaysBreakTemplateDeclarations: MultiLine
|
||||||
|
BinPackArguments: true
|
||||||
|
BinPackParameters: true
|
||||||
|
BraceWrapping:
|
||||||
|
AfterClass: false
|
||||||
|
AfterControlStatement: false
|
||||||
|
AfterEnum: false
|
||||||
|
AfterFunction: false
|
||||||
|
AfterNamespace: false
|
||||||
|
AfterObjCDeclaration: false
|
||||||
|
AfterStruct: false
|
||||||
|
AfterUnion: false
|
||||||
|
AfterExternBlock: false
|
||||||
|
BeforeCatch: false
|
||||||
|
BeforeElse: false
|
||||||
|
IndentBraces: false
|
||||||
|
SplitEmptyFunction: true
|
||||||
|
SplitEmptyRecord: true
|
||||||
|
SplitEmptyNamespace: true
|
||||||
|
BreakBeforeBinaryOperators: None
|
||||||
|
BreakBeforeBraces: Attach
|
||||||
|
BreakBeforeInheritanceComma: false
|
||||||
|
BreakInheritanceList: BeforeColon
|
||||||
|
BreakBeforeTernaryOperators: true
|
||||||
|
BreakConstructorInitializersBeforeComma: false
|
||||||
|
BreakConstructorInitializers: BeforeColon
|
||||||
|
BreakAfterJavaFieldAnnotations: false
|
||||||
|
BreakStringLiterals: true
|
||||||
|
ColumnLimit: 80
|
||||||
|
CommentPragmas: '^ IWYU pragma:'
|
||||||
|
CompactNamespaces: false
|
||||||
|
ConstructorInitializerAllOnOneLineOrOnePerLine: false
|
||||||
|
ConstructorInitializerIndentWidth: 4
|
||||||
|
ContinuationIndentWidth: 4
|
||||||
|
Cpp11BracedListStyle: true
|
||||||
|
DerivePointerAlignment: false
|
||||||
|
DisableFormat: false
|
||||||
|
ExperimentalAutoDetectBinPacking: false
|
||||||
|
FixNamespaceComments: true
|
||||||
|
ForEachMacros:
|
||||||
|
- foreach
|
||||||
|
- Q_FOREACH
|
||||||
|
- BOOST_FOREACH
|
||||||
|
IncludeBlocks: Preserve
|
||||||
|
IncludeCategories:
|
||||||
|
- Regex: '^"(llvm|llvm-c|clang|clang-c)/'
|
||||||
|
Priority: 2
|
||||||
|
- Regex: '^(<|"(gtest|gmock|isl|json)/)'
|
||||||
|
Priority: 3
|
||||||
|
- Regex: '.*'
|
||||||
|
Priority: 1
|
||||||
|
IncludeIsMainRegex: '(Test)?$'
|
||||||
|
IndentCaseLabels: false
|
||||||
|
IndentPPDirectives: None
|
||||||
|
IndentWidth: 2
|
||||||
|
IndentWrappedFunctionNames: false
|
||||||
|
JavaScriptQuotes: Leave
|
||||||
|
JavaScriptWrapImports: true
|
||||||
|
KeepEmptyLinesAtTheStartOfBlocks: true
|
||||||
|
MacroBlockBegin: ''
|
||||||
|
MacroBlockEnd: ''
|
||||||
|
MaxEmptyLinesToKeep: 1
|
||||||
|
NamespaceIndentation: None
|
||||||
|
ObjCBinPackProtocolList: Auto
|
||||||
|
ObjCBlockIndentWidth: 2
|
||||||
|
ObjCSpaceAfterProperty: false
|
||||||
|
ObjCSpaceBeforeProtocolList: true
|
||||||
|
PenaltyBreakAssignment: 2
|
||||||
|
PenaltyBreakBeforeFirstCallParameter: 19
|
||||||
|
PenaltyBreakComment: 300
|
||||||
|
PenaltyBreakFirstLessLess: 120
|
||||||
|
PenaltyBreakString: 1000
|
||||||
|
PenaltyBreakTemplateDeclaration: 10
|
||||||
|
PenaltyExcessCharacter: 1000000
|
||||||
|
PenaltyReturnTypeOnItsOwnLine: 60
|
||||||
|
PointerAlignment: Right
|
||||||
|
ReflowComments: true
|
||||||
|
SortIncludes: true
|
||||||
|
SortUsingDeclarations: true
|
||||||
|
SpaceAfterCStyleCast: false
|
||||||
|
SpaceAfterTemplateKeyword: true
|
||||||
|
SpaceBeforeAssignmentOperators: true
|
||||||
|
SpaceBeforeCpp11BracedList: false
|
||||||
|
SpaceBeforeCtorInitializerColon: true
|
||||||
|
SpaceBeforeInheritanceColon: true
|
||||||
|
SpaceBeforeParens: ControlStatements
|
||||||
|
SpaceBeforeRangeBasedForLoopColon: true
|
||||||
|
SpaceInEmptyParentheses: false
|
||||||
|
SpacesBeforeTrailingComments: 1
|
||||||
|
SpacesInAngles: false
|
||||||
|
SpacesInContainerLiterals: true
|
||||||
|
SpacesInCStyleCastParentheses: false
|
||||||
|
SpacesInParentheses: false
|
||||||
|
SpacesInSquareBrackets: false
|
||||||
|
Standard: Cpp11
|
||||||
|
StatementMacros:
|
||||||
|
- Q_UNUSED
|
||||||
|
- QT_REQUIRE_VERSION
|
||||||
|
TabWidth: 8
|
||||||
|
UseTab: Never
|
||||||
|
...
|
||||||
|
|
@ -11,51 +11,43 @@ namespace ros = ::rclcpp;
|
|||||||
using UaspireCommand = ::uaspire_msgs::msg::Command;
|
using UaspireCommand = ::uaspire_msgs::msg::Command;
|
||||||
using UaspireSensors = ::uaspire_msgs::msg::Sensors;
|
using UaspireSensors = ::uaspire_msgs::msg::Sensors;
|
||||||
|
|
||||||
class ControlsNode : public ros::Node
|
class ControlsNode : public ros::Node {
|
||||||
{
|
|
||||||
private:
|
private:
|
||||||
ros::Subscription<UaspireCommand>::SharedPtr _command_subscription;
|
ros::Subscription<UaspireCommand>::SharedPtr _command_subscription;
|
||||||
ros::Publisher<UaspireSensors>::SharedPtr _sensors_publisher;
|
ros::Publisher<UaspireSensors>::SharedPtr _sensors_publisher;
|
||||||
ros::TimerBase::SharedPtr _timer;
|
ros::TimerBase::SharedPtr _timer;
|
||||||
|
|
||||||
public:
|
public:
|
||||||
RCLCPP_SHARED_PTR_DEFINITIONS(ControlsNode)
|
RCLCPP_SHARED_PTR_DEFINITIONS(ControlsNode)
|
||||||
|
|
||||||
ControlsNode()
|
ControlsNode() : Node("uaspire_controls") {
|
||||||
: Node("uaspire_controls")
|
_command_subscription = create_subscription<UaspireCommand>(
|
||||||
{
|
"uaspire/commands", ros::QoS(10),
|
||||||
_command_subscription = create_subscription<UaspireCommand>(
|
std::bind(&ControlsNode::on_message, this, arg::_1));
|
||||||
"uaspire/commands",
|
_sensors_publisher =
|
||||||
ros::QoS(10),
|
create_publisher<UaspireSensors>("uaspire/sensors", ros::QoS(10));
|
||||||
std::bind(&ControlsNode::on_message, this, arg::_1)
|
_timer = create_wall_timer(std::chrono::milliseconds(1000),
|
||||||
);
|
std::bind(&ControlsNode::on_loop, this));
|
||||||
_sensors_publisher = create_publisher<UaspireSensors>(
|
}
|
||||||
"uaspire/sensors",
|
|
||||||
ros::QoS(10)
|
|
||||||
);
|
|
||||||
_timer = create_wall_timer(std::chrono::milliseconds(1000),
|
|
||||||
std::bind(&ControlsNode::on_loop, this));
|
|
||||||
}
|
|
||||||
|
|
||||||
void on_message(const UaspireCommand::SharedPtr cmd)
|
void on_message(const UaspireCommand::SharedPtr cmd) {
|
||||||
{
|
RCLCPP_INFO(get_logger(), "Command received: %s", cmd->data.c_str());
|
||||||
RCLCPP_INFO(get_logger(), "Command received: %s", cmd->data.c_str());
|
}
|
||||||
}
|
|
||||||
|
|
||||||
void on_loop() {
|
void on_loop() {
|
||||||
UaspireSensors sensors;
|
UaspireSensors sensors;
|
||||||
sensors.position = ros::Clock(RCL_STEADY_TIME).now().seconds();
|
sensors.position = ros::Clock(RCL_STEADY_TIME).now().seconds();
|
||||||
_sensors_publisher->publish(sensors);
|
_sensors_publisher->publish(sensors);
|
||||||
RCLCPP_INFO(get_logger(), "loop");
|
RCLCPP_INFO(get_logger(), "loop");
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
int main(int argc, char** argv) {
|
int main(int argc, char **argv) {
|
||||||
ros::init(argc, argv);
|
ros::init(argc, argv);
|
||||||
{
|
{
|
||||||
auto node = ControlsNode::make_shared();
|
auto node = ControlsNode::make_shared();
|
||||||
ros::spin(node);
|
ros::spin(node);
|
||||||
}
|
}
|
||||||
ros::shutdown();
|
ros::shutdown();
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
Loading…
x
Reference in New Issue
Block a user