Skip to content

Commit 47b8adf

Browse files
committed
Don't align declarations, don't pack parameters
1 parent 1e1583a commit 47b8adf

File tree

5 files changed

+122
-119
lines changed

5 files changed

+122
-119
lines changed

puma_motor_driver/.clang-format

+4-5
Original file line numberDiff line numberDiff line change
@@ -2,13 +2,12 @@
22
BasedOnStyle: Google
33
AccessModifierOffset: -2
44
ConstructorInitializerIndentWidth: 2
5-
AlignEscapedNewlinesLeft: false
6-
AlignTrailingComments: true
75
AlignAfterOpenBracket: Align
8-
AlignConsecutiveAssignments: AcrossEmptyLines
9-
AlignConsecutiveDeclarations: AcrossEmptyLines
6+
AlignConsecutiveAssignments: false
7+
AlignConsecutiveDeclarations: false
108
AlignConsecutiveMacros: AcrossEmptyLines
119
AlignEscapedNewlines: LeftWithLastLine
10+
AlignTrailingComments: true
1211
AllowAllParametersOfDeclarationOnNextLine: false
1312
AllowShortIfStatementsOnASingleLine: false
1413
AllowShortLoopsOnASingleLine: false
@@ -18,7 +17,7 @@ AlwaysBreakBeforeMultilineStrings: true
1817
BreakBeforeBinaryOperators: false
1918
BreakBeforeTernaryOperators: false
2019
BreakConstructorInitializersBeforeComma: true
21-
BinPackParameters: true
20+
BinPackParameters: false
2221
ColumnLimit: 120
2322
ConstructorInitializerAllOnOneLineOrOnePerLine: true
2423
DerivePointerBinding: false

puma_motor_driver/include/puma_motor_driver/driver.hpp

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

45-
void processMessage(const can_msgs::msg::Frame::SharedPtr received_msg);
47+
void processMessage(const can_msgs::msg::Frame::SharedPtr received_msg);
4648

4749
double radPerSecToRpm() const;
4850

@@ -433,7 +435,7 @@ class Driver
433435
*
434436
* @return value of the set-point response.
435437
*/
436-
double statusPositionGet();
438+
double statusPositionGet();
437439

438440
std::string deviceName() const
439441
{
@@ -449,9 +451,9 @@ class Driver
449451
struct Field
450452
{
451453
uint8_t data[4];
452-
bool received;
454+
bool received;
453455

454-
float interpretFixed8x8()
456+
float interpretFixed8x8()
455457
{
456458
return *(reinterpret_cast<int16_t*>(data)) / static_cast<float>(1 << 8);
457459
}
@@ -464,32 +466,32 @@ class Driver
464466

465467
private:
466468
std::shared_ptr<clearpath_ros2_socketcan_interface::SocketCANInterface> interface_;
467-
std::shared_ptr<rclcpp::Node> nh_;
468-
uint8_t device_number_;
469-
std::string device_name_;
469+
std::shared_ptr<rclcpp::Node> nh_;
470+
uint8_t device_number_;
471+
std::string device_name_;
470472

471-
bool configured_;
472-
uint8_t state_;
473+
bool configured_;
474+
uint8_t state_;
473475

474-
uint8_t control_mode_;
475-
double gain_p_;
476-
double gain_i_;
477-
double gain_d_;
478-
uint16_t encoder_cpr_;
479-
float gear_ratio_;
476+
uint8_t control_mode_;
477+
double gain_p_;
478+
double gain_i_;
479+
double gain_d_;
480+
uint16_t encoder_cpr_;
481+
float gear_ratio_;
480482

481483
/**
482484
* Helpers to generate data for CAN messages.
483485
*/
484486
can_msgs::msg::Frame::SharedPtr can_msg_;
485-
void sendId(const uint32_t id);
486-
void sendUint8(const uint32_t id, const uint8_t value);
487-
void sendUint16(const uint32_t id, const uint16_t value);
488-
void sendFixed8x8(const uint32_t id, const float value);
489-
void sendFixed16x16(const uint32_t id, const double value);
490-
can_msgs::msg::Frame getMsg(const uint32_t id);
491-
uint32_t getApi(const can_msgs::msg::Frame msg);
492-
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);
493495

494496
/**
495497
* Comparing the raw bytes of the 16x16 fixed-point numbers
@@ -505,15 +507,15 @@ class Driver
505507
*
506508
* @return boolean if received is equal to expected.
507509
*/
508-
bool verifyRaw8x8(const uint8_t* received, const float expected);
510+
bool verifyRaw8x8(const uint8_t* received, const float expected);
509511

510-
Field voltage_fields_[4];
511-
Field spd_fields_[7];
512-
Field vcomp_fields_[5];
513-
Field pos_fields_[7];
514-
Field ictrl_fields_[6];
515-
Field status_fields_[15];
516-
Field cfg_fields_[15];
512+
Field voltage_fields_[4];
513+
Field spd_fields_[7];
514+
Field vcomp_fields_[5];
515+
Field pos_fields_[7];
516+
Field ictrl_fields_[6];
517+
Field status_fields_[15];
518+
Field cfg_fields_[15];
517519

518520
Field* voltageFieldForMessage(uint32_t api);
519521
Field* spdFieldForMessage(uint32_t api);

puma_motor_driver/include/puma_motor_driver/multi_puma_node.hpp

+26-26
Original file line numberDiff line numberDiff line change
@@ -117,33 +117,33 @@ class MultiPumaNode : public rclcpp::Node
117117
void run();
118118

119119
private:
120-
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_;
130-
std::vector<std::string> joint_names_;
131-
std::vector<int64_t> joint_can_ids_;
132-
std::vector<int64_t> joint_directions_;
133-
134-
can_msgs::msg::Frame::SharedPtr recv_msg_;
135-
clearpath_motor_msgs::msg::PumaMultiStatus status_msg_;
136-
clearpath_motor_msgs::msg::PumaMultiFeedback feedback_msg_;
137-
138-
double gain_p_;
139-
double gain_i_;
140-
double gain_d_;
141-
142-
rclcpp::Node::SharedPtr node_handle_;
143-
rclcpp::Publisher<clearpath_motor_msgs::msg::PumaMultiStatus>::SharedPtr status_pub_;
120+
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_;
130+
std::vector<std::string> joint_names_;
131+
std::vector<int64_t> joint_can_ids_;
132+
std::vector<int64_t> joint_directions_;
133+
134+
can_msgs::msg::Frame::SharedPtr recv_msg_;
135+
clearpath_motor_msgs::msg::PumaMultiStatus status_msg_;
136+
clearpath_motor_msgs::msg::PumaMultiFeedback feedback_msg_;
137+
138+
double gain_p_;
139+
double gain_i_;
140+
double gain_d_;
141+
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)