Skip to content

Commit 1e1583a

Browse files
committed
Update alignment.
1 parent 5626796 commit 1e1583a

File tree

6 files changed

+267
-262
lines changed

6 files changed

+267
-262
lines changed

puma_motor_driver/.clang-format

+5
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,11 @@ AccessModifierOffset: -2
44
ConstructorInitializerIndentWidth: 2
55
AlignEscapedNewlinesLeft: false
66
AlignTrailingComments: true
7+
AlignAfterOpenBracket: Align
8+
AlignConsecutiveAssignments: AcrossEmptyLines
9+
AlignConsecutiveDeclarations: AcrossEmptyLines
10+
AlignConsecutiveMacros: AcrossEmptyLines
11+
AlignEscapedNewlines: LeftWithLastLine
712
AllowAllParametersOfDeclarationOnNextLine: false
813
AllowShortIfStatementsOnASingleLine: false
914
AllowShortLoopsOnASingleLine: false

puma_motor_driver/include/puma_motor_driver/can_proto.hpp

+150-150
Large diffs are not rendered by default.

puma_motor_driver/include/puma_motor_driver/driver.hpp

+31-31
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,7 @@ class Driver
4242
Driver(const std::shared_ptr<clearpath_ros2_socketcan_interface::SocketCANInterface> interface,
4343
std::shared_ptr<rclcpp::Node> nh, const uint8_t& device_number, const std::string& device_name);
4444

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

4747
double radPerSecToRpm() const;
4848

@@ -433,7 +433,7 @@ class Driver
433433
*
434434
* @return value of the set-point response.
435435
*/
436-
double statusPositionGet();
436+
double statusPositionGet();
437437

438438
std::string deviceName() const
439439
{
@@ -449,9 +449,9 @@ class Driver
449449
struct Field
450450
{
451451
uint8_t data[4];
452-
bool received;
452+
bool received;
453453

454-
float interpretFixed8x8()
454+
float interpretFixed8x8()
455455
{
456456
return *(reinterpret_cast<int16_t*>(data)) / static_cast<float>(1 << 8);
457457
}
@@ -464,32 +464,32 @@ class Driver
464464

465465
private:
466466
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_;
467+
std::shared_ptr<rclcpp::Node> nh_;
468+
uint8_t device_number_;
469+
std::string device_name_;
470470

471-
bool configured_;
472-
uint8_t state_;
471+
bool configured_;
472+
uint8_t state_;
473473

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_;
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_;
480480

481481
/**
482482
* Helpers to generate data for CAN messages.
483483
*/
484484
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);
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);
493493

494494
/**
495495
* Comparing the raw bytes of the 16x16 fixed-point numbers
@@ -505,15 +505,15 @@ class Driver
505505
*
506506
* @return boolean if received is equal to expected.
507507
*/
508-
bool verifyRaw8x8(const uint8_t* received, const float expected);
508+
bool verifyRaw8x8(const uint8_t* received, const float expected);
509509

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];
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];
517517

518518
Field* voltageFieldForMessage(uint32_t api);
519519
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

puma_motor_driver/src/driver.cpp

+33-33
Original file line numberDiff line numberDiff line change
@@ -87,7 +87,7 @@ void Driver::processMessage(const can_msgs::msg::Frame::SharedPtr received_msg)
8787
return;
8888
}
8989

90-
Field* field = nullptr;
90+
Field* field = nullptr;
9191
uint32_t received_api = getApi(*received_msg);
9292
if ((received_api & CAN_MSGID_API_M & CAN_API_MC_CFG) == CAN_API_MC_CFG)
9393
{
@@ -142,8 +142,8 @@ void Driver::sendId(const uint32_t id)
142142
void Driver::sendUint8(const uint32_t id, const uint8_t value)
143143
{
144144
can_msgs::msg::Frame msg = getMsg(id);
145-
msg.dlc = sizeof(uint8_t);
146-
uint8_t data[8] = { 0 };
145+
msg.dlc = sizeof(uint8_t);
146+
uint8_t data[8] = { 0 };
147147
std::memcpy(data, &value, sizeof(uint8_t));
148148
std::copy(std::begin(data), std::end(data), std::begin(msg.data));
149149

@@ -153,8 +153,8 @@ void Driver::sendUint8(const uint32_t id, const uint8_t value)
153153
void Driver::sendUint16(const uint32_t id, const uint16_t value)
154154
{
155155
can_msgs::msg::Frame msg = getMsg(id);
156-
msg.dlc = sizeof(uint16_t);
157-
uint8_t data[8] = { 0 };
156+
msg.dlc = sizeof(uint16_t);
157+
uint8_t data[8] = { 0 };
158158
std::memcpy(data, &value, sizeof(uint16_t));
159159
std::copy(std::begin(data), std::end(data), std::begin(msg.data));
160160

@@ -164,10 +164,10 @@ void Driver::sendUint16(const uint32_t id, const uint16_t value)
164164
void Driver::sendFixed8x8(const uint32_t id, const float value)
165165
{
166166
can_msgs::msg::Frame msg = getMsg(id);
167-
msg.dlc = sizeof(int16_t);
168-
int16_t output_value = static_cast<int16_t>(static_cast<float>(1 << 8) * value);
167+
msg.dlc = sizeof(int16_t);
168+
int16_t output_value = static_cast<int16_t>(static_cast<float>(1 << 8) * value);
169169

170-
uint8_t data[8] = { 0 };
170+
uint8_t data[8] = { 0 };
171171
std::memcpy(data, &output_value, sizeof(int16_t));
172172
std::copy(std::begin(data), std::end(data), std::begin(msg.data));
173173

@@ -177,10 +177,10 @@ void Driver::sendFixed8x8(const uint32_t id, const float value)
177177
void Driver::sendFixed16x16(const uint32_t id, const double value)
178178
{
179179
can_msgs::msg::Frame msg = getMsg(id);
180-
msg.dlc = sizeof(int32_t);
181-
int32_t output_value = static_cast<int32_t>(static_cast<double>((1 << 16) * value));
180+
msg.dlc = sizeof(int32_t);
181+
int32_t output_value = static_cast<int32_t>(static_cast<double>((1 << 16) * value));
182182

183-
uint8_t data[8] = { 0 };
183+
uint8_t data[8] = { 0 };
184184
std::memcpy(data, &output_value, sizeof(int32_t));
185185
std::copy(std::begin(data), std::end(data), std::begin(msg.data));
186186

@@ -190,10 +190,10 @@ void Driver::sendFixed16x16(const uint32_t id, const double value)
190190
can_msgs::msg::Frame Driver::getMsg(const uint32_t id)
191191
{
192192
can_msgs::msg::Frame msg;
193-
msg.id = id;
194-
msg.dlc = 0;
195-
msg.is_extended = true;
196-
msg.header.stamp = nh_->get_clock()->now();
193+
msg.id = id;
194+
msg.dlc = 0;
195+
msg.is_extended = true;
196+
msg.header.stamp = nh_->get_clock()->now();
197197
msg.header.frame_id = "base_link";
198198
return msg;
199199
}
@@ -437,7 +437,7 @@ void Driver::verifyParams()
437437
RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Puma Motor Controller on %s (%i): all parameters verified.",
438438
device_name_.c_str(), device_number_);
439439
configured_ = true;
440-
state_ = ConfigurationState::Configured;
440+
state_ = ConfigurationState::Configured;
441441
}
442442
}
443443

@@ -663,13 +663,13 @@ void Driver::requestFeedbackSetpoint()
663663
void Driver::resetConfiguration()
664664
{
665665
configured_ = false;
666-
state_ = ConfigurationState::Initializing;
666+
state_ = ConfigurationState::Initializing;
667667
}
668668

669669
void Driver::updateGains()
670670
{
671671
configured_ = false;
672-
state_ = ConfigurationState::PGain;
672+
state_ = ConfigurationState::PGain;
673673
}
674674

675675
bool Driver::receivedDutyCycle()
@@ -786,77 +786,77 @@ bool Driver::receivedPositionSetpoint()
786786

787787
float Driver::lastDutyCycle()
788788
{
789-
Field* field = statusFieldForMessage(getApi(getMsg(LM_API_STATUS_VOLTOUT)));
789+
Field* field = statusFieldForMessage(getApi(getMsg(LM_API_STATUS_VOLTOUT)));
790790
field->received = false;
791791
return field->interpretFixed8x8() / 128.0;
792792
}
793793

794794
float Driver::lastBusVoltage()
795795
{
796-
Field* field = statusFieldForMessage(getApi(getMsg(LM_API_STATUS_VOLTBUS)));
796+
Field* field = statusFieldForMessage(getApi(getMsg(LM_API_STATUS_VOLTBUS)));
797797
field->received = false;
798798
return field->interpretFixed8x8();
799799
}
800800

801801
float Driver::lastCurrent()
802802
{
803-
Field* field = statusFieldForMessage(getApi(getMsg(LM_API_STATUS_CURRENT)));
803+
Field* field = statusFieldForMessage(getApi(getMsg(LM_API_STATUS_CURRENT)));
804804
field->received = false;
805805
return field->interpretFixed8x8();
806806
}
807807

808808
double Driver::lastPosition()
809809
{
810-
Field* field = statusFieldForMessage(getApi(getMsg(LM_API_STATUS_POS)));
810+
Field* field = statusFieldForMessage(getApi(getMsg(LM_API_STATUS_POS)));
811811
field->received = false;
812812
return field->interpretFixed16x16() * ((2 * M_PI) / gear_ratio_); // Convert rev to rad
813813
}
814814

815815
double Driver::lastSpeed()
816816
{
817-
Field* field = statusFieldForMessage(getApi(getMsg(LM_API_STATUS_SPD)));
817+
Field* field = statusFieldForMessage(getApi(getMsg(LM_API_STATUS_SPD)));
818818
field->received = false;
819819
return field->interpretFixed16x16() * ((2 * M_PI) / (gear_ratio_ * 60)); // Convert RPM to rad/s
820820
}
821821

822822
uint8_t Driver::lastFault()
823823
{
824-
Field* field = statusFieldForMessage(getApi(getMsg(LM_API_STATUS_FAULT)));
824+
Field* field = statusFieldForMessage(getApi(getMsg(LM_API_STATUS_FAULT)));
825825
field->received = false;
826826
return field->data[0];
827827
}
828828

829829
uint8_t Driver::lastPower()
830830
{
831-
Field* field = statusFieldForMessage(getApi(getMsg(LM_API_STATUS_POWER)));
831+
Field* field = statusFieldForMessage(getApi(getMsg(LM_API_STATUS_POWER)));
832832
field->received = false;
833833
return field->data[0];
834834
}
835835

836836
uint8_t Driver::lastMode()
837837
{
838-
Field* field = statusFieldForMessage(getApi(getMsg(LM_API_STATUS_CMODE)));
838+
Field* field = statusFieldForMessage(getApi(getMsg(LM_API_STATUS_CMODE)));
839839
field->received = false;
840840
return field->data[0];
841841
}
842842

843843
float Driver::lastOutVoltage()
844844
{
845-
Field* field = statusFieldForMessage(getApi(getMsg(LM_API_STATUS_VOUT)));
845+
Field* field = statusFieldForMessage(getApi(getMsg(LM_API_STATUS_VOUT)));
846846
field->received = false;
847847
return field->interpretFixed8x8();
848848
}
849849

850850
float Driver::lastTemperature()
851851
{
852-
Field* field = statusFieldForMessage(getApi(getMsg(LM_API_STATUS_TEMP)));
852+
Field* field = statusFieldForMessage(getApi(getMsg(LM_API_STATUS_TEMP)));
853853
field->received = false;
854854
return field->interpretFixed8x8();
855855
}
856856

857857
float Driver::lastAnalogInput()
858858
{
859-
Field* field = statusFieldForMessage(getApi(getMsg(CPR_API_STATUS_ANALOG)));
859+
Field* field = statusFieldForMessage(getApi(getMsg(CPR_API_STATUS_ANALOG)));
860860
field->received = false;
861861
return field->interpretFixed8x8();
862862
}
@@ -884,28 +884,28 @@ double Driver::lastSetpoint()
884884
}
885885
double Driver::statusSpeedGet()
886886
{
887-
Field* field = spdFieldForMessage(getApi(getMsg(LM_API_SPD_SET)));
887+
Field* field = spdFieldForMessage(getApi(getMsg(LM_API_SPD_SET)));
888888
field->received = false;
889889
return field->interpretFixed16x16() * ((2 * M_PI) / (gear_ratio_ * 60)); // Convert RPM to rad/s
890890
}
891891

892892
float Driver::statusDutyCycleGet()
893893
{
894-
Field* field = voltageFieldForMessage(getApi(getMsg(LM_API_VOLT_SET)));
894+
Field* field = voltageFieldForMessage(getApi(getMsg(LM_API_VOLT_SET)));
895895
field->received = false;
896896
return field->interpretFixed8x8() / 128.0;
897897
}
898898

899899
float Driver::statusCurrentGet()
900900
{
901-
Field* field = ictrlFieldForMessage(getApi(getMsg(LM_API_ICTRL_SET)));
901+
Field* field = ictrlFieldForMessage(getApi(getMsg(LM_API_ICTRL_SET)));
902902
field->received = false;
903903
return field->interpretFixed8x8();
904904
}
905905

906906
double Driver::statusPositionGet()
907907
{
908-
Field* field = posFieldForMessage(getApi(getMsg(LM_API_POS_SET)));
908+
Field* field = posFieldForMessage(getApi(getMsg(LM_API_POS_SET)));
909909
field->received = false;
910910
return field->interpretFixed16x16() * ((2 * M_PI) / gear_ratio_); // Convert rev to rad
911911
}

0 commit comments

Comments
 (0)