Skip to content

Commit 8941c75

Browse files
committed
pre-commit checks
1 parent ad292a2 commit 8941c75

File tree

4 files changed

+52
-39
lines changed

4 files changed

+52
-39
lines changed

Diff for: demo/CMakeLists.txt

+1-3
Original file line numberDiff line numberDiff line change
@@ -10,9 +10,7 @@ add_executable(stiffness_gui src/control_gui.cpp)
1010
target_link_libraries(stiffness_gui Qt5::Widgets)
1111
ament_target_dependencies(stiffness_gui rclcpp std_msgs)
1212

13-
install(TARGETS stiffness_gui
14-
DESTINATION lib/${PROJECT_NAME}
15-
)
13+
install(TARGETS stiffness_gui DESTINATION lib/${PROJECT_NAME})
1614

1715
install(TARGETS pipeline_testbench_example constrained_planning_demo
1816
DESTINATION lib/${PROJECT_NAME})

Diff for: demo/src/control_gui.cpp

+15-14
Original file line numberDiff line numberDiff line change
@@ -7,14 +7,16 @@
77
#include <rclcpp/rclcpp.hpp>
88
#include <std_msgs/msg/float64_multi_array.hpp>
99

10-
class StiffnessGUI : public QWidget {
10+
class StiffnessGUI : public QWidget
11+
{
1112
Q_OBJECT
1213

1314
public:
14-
StiffnessGUI(std::shared_ptr<rclcpp::Node> node) : node_(node) {
15+
StiffnessGUI(std::shared_ptr<rclcpp::Node> node) : node_(node)
16+
{
1517
publisher_ = node_->create_publisher<std_msgs::msg::Float64MultiArray>("/joint_stiffness_controller/command", 10);
1618

17-
auto *layout = new QVBoxLayout(this);
19+
auto* layout = new QVBoxLayout(this);
1820

1921
pos_spin1 = new QDoubleSpinBox();
2022
pos_spin2 = new QDoubleSpinBox();
@@ -30,32 +32,31 @@ class StiffnessGUI : public QWidget {
3032
layout->addWidget(new QLabel("Stiffness Joint 2"));
3133
layout->addWidget(stiff_spin2);
3234

33-
auto *send_btn = new QPushButton("Send Command");
35+
auto* send_btn = new QPushButton("Send Command");
3436
layout->addWidget(send_btn);
3537
connect(send_btn, &QPushButton::clicked, this, &StiffnessGUI::send_command);
3638
}
3739

3840
private slots:
39-
void send_command() {
41+
void send_command()
42+
{
4043
auto msg = std_msgs::msg::Float64MultiArray();
41-
msg.data = {
42-
pos_spin1->value(), pos_spin2->value(),
43-
stiff_spin1->value(), stiff_spin2->value()
44-
};
44+
msg.data = { pos_spin1->value(), pos_spin2->value(), stiff_spin1->value(), stiff_spin2->value() };
4545
publisher_->publish(msg);
4646
}
4747

4848
private:
4949
std::shared_ptr<rclcpp::Node> node_;
5050
rclcpp::Publisher<std_msgs::msg::Float64MultiArray>::SharedPtr publisher_;
5151

52-
QDoubleSpinBox *pos_spin1;
53-
QDoubleSpinBox *pos_spin2;
54-
QDoubleSpinBox *stiff_spin1;
55-
QDoubleSpinBox *stiff_spin2;
52+
QDoubleSpinBox* pos_spin1;
53+
QDoubleSpinBox* pos_spin2;
54+
QDoubleSpinBox* stiff_spin1;
55+
QDoubleSpinBox* stiff_spin2;
5656
};
5757

58-
int main(int argc, char **argv) {
58+
int main(int argc, char** argv)
59+
{
5960
rclcpp::init(argc, argv);
6061
QApplication app(argc, argv);
6162

Diff for: include/stiffness_control/joint_stiffness_controller.hpp

+6-4
Original file line numberDiff line numberDiff line change
@@ -6,9 +6,11 @@
66
#include <hardware_interface/loaned_state_interface.hpp>
77
#include <std_msgs/msg/float64_multi_array.hpp>
88

9-
namespace joint_stiffness_controller {
9+
namespace joint_stiffness_controller
10+
{
1011

11-
class JointStiffnessController : public controller_interface::ControllerInterface {
12+
class JointStiffnessController : public controller_interface::ControllerInterface
13+
{
1214
public:
1315
JointStiffnessController();
1416

@@ -25,8 +27,8 @@ class JointStiffnessController : public controller_interface::ControllerInterfac
2527
rclcpp::Subscription<std_msgs::msg::Float64MultiArray>::SharedPtr command_sub_;
2628
std::vector<double> desired_positions_;
2729
std::vector<double> stiffness_gains_;
28-
30+
2931
void command_callback(const std_msgs::msg::Float64MultiArray::SharedPtr msg);
3032
};
3133

32-
} // namespace joint_stiffness_controller
34+
} // namespace joint_stiffness_controller

Diff for: src/joint_stiffness_controller.cpp

+30-18
Original file line numberDiff line numberDiff line change
@@ -1,58 +1,70 @@
11
#include "stiffness_control/joint_stiffness_controller.hpp"
22

3-
namespace joint_stiffness_controller {
3+
namespace joint_stiffness_controller
4+
{
45

5-
JointStiffnessController::JointStiffnessController() {}
6+
JointStiffnessController::JointStiffnessController()
7+
{
8+
}
69

7-
controller_interface::CallbackReturn JointStiffnessController::on_init() {
10+
controller_interface::CallbackReturn JointStiffnessController::on_init()
11+
{
812
return controller_interface::CallbackReturn::SUCCESS;
913
}
1014

11-
controller_interface::CallbackReturn JointStiffnessController::on_configure(const rclcpp_lifecycle::State&) {
15+
controller_interface::CallbackReturn JointStiffnessController::on_configure(const rclcpp_lifecycle::State&)
16+
{
1217
auto node = get_node();
1318
command_sub_ = node->create_subscription<std_msgs::msg::Float64MultiArray>(
14-
"~/command", 10, std::bind(&JointStiffnessController::command_callback, this, std::placeholders::_1));
19+
"~/command", 10, std::bind(&JointStiffnessController::command_callback, this, std::placeholders::_1));
1520
return controller_interface::CallbackReturn::SUCCESS;
1621
}
1722

18-
controller_interface::InterfaceConfiguration JointStiffnessController::command_interface_configuration() const {
23+
controller_interface::InterfaceConfiguration JointStiffnessController::command_interface_configuration() const
24+
{
1925
return {
2026
controller_interface::interface_configuration_type::INDIVIDUAL,
21-
{"joint1/position", "joint2/position"} // replace with your actual joints
27+
{ "joint1/position", "joint2/position" } // replace with your actual joints
2228
};
2329
}
2430

25-
controller_interface::InterfaceConfiguration JointStiffnessController::state_interface_configuration() const {
31+
controller_interface::InterfaceConfiguration JointStiffnessController::state_interface_configuration() const
32+
{
2633
return {
2734
controller_interface::interface_configuration_type::INDIVIDUAL,
28-
{"joint1/position", "joint2/position"} // same joints
35+
{ "joint1/position", "joint2/position" } // same joints
2936
};
3037
}
3138

32-
void JointStiffnessController::command_callback(const std_msgs::msg::Float64MultiArray::SharedPtr msg) {
39+
void JointStiffnessController::command_callback(const std_msgs::msg::Float64MultiArray::SharedPtr msg)
40+
{
3341
size_t n = msg->data.size() / 2;
3442
desired_positions_.resize(n);
3543
stiffness_gains_.resize(n);
36-
for (size_t i = 0; i < n; ++i) {
44+
for (size_t i = 0; i < n; ++i)
45+
{
3746
desired_positions_[i] = msg->data[i];
3847
stiffness_gains_[i] = msg->data[i + n];
3948
}
4049
}
4150

42-
controller_interface::return_type JointStiffnessController::update(
43-
const rclcpp::Time&, const rclcpp::Duration&) {
44-
for (size_t i = 0; i < position_cmd_handles_.size(); ++i) {
51+
controller_interface::return_type JointStiffnessController::update(const rclcpp::Time&, const rclcpp::Duration&)
52+
{
53+
for (size_t i = 0; i < position_cmd_handles_.size(); ++i)
54+
{
4555
double error = desired_positions_[i] - position_state_handles_[i].get_optional().value_or(0.0);
4656
double command = stiffness_gains_[i] * error;
47-
bool success = position_cmd_handles_[i].set_value(position_state_handles_[i].get_optional().value_or(0.0) + command);
48-
if (!success) {
57+
bool success =
58+
position_cmd_handles_[i].set_value(position_state_handles_[i].get_optional().value_or(0.0) + command);
59+
if (!success)
60+
{
4961
RCLCPP_WARN(get_node()->get_logger(), "Failed to set command for joint %zu", i);
50-
}
62+
}
5163
}
5264
return controller_interface::return_type::OK;
5365
}
5466

55-
} // namespace joint_stiffness_controller
67+
} // namespace joint_stiffness_controller
5668

5769
#include "pluginlib/class_list_macros.hpp"
5870
PLUGINLIB_EXPORT_CLASS(joint_stiffness_controller::JointStiffnessController, controller_interface::ControllerInterface)

0 commit comments

Comments
 (0)