Skip to content

Commit 1e58594

Browse files
committed
Apply formatting
1 parent 743f231 commit 1e58594

93 files changed

Lines changed: 424 additions & 426 deletions

File tree

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

src/bitbots_lowlevel/bitbots_ros_control/include/bitbots_ros_control/bitfoot_hardware_interface.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -14,14 +14,14 @@ namespace bitbots_ros_control {
1414

1515
class BitFootHardwareInterface : public bitbots_ros_control::HardwareInterface {
1616
public:
17-
explicit BitFootHardwareInterface(rclcpp::Node::SharedPtr nh, std::shared_ptr<DynamixelDriver> &driver, int id,
17+
explicit BitFootHardwareInterface(rclcpp::Node::SharedPtr nh, std::shared_ptr<DynamixelDriver>& driver, int id,
1818
std::string topic_name, std::string name);
1919

2020
bool init();
2121

22-
void read(const rclcpp::Time &t, const rclcpp::Duration &dt);
22+
void read(const rclcpp::Time& t, const rclcpp::Duration& dt);
2323

24-
void write(const rclcpp::Time &t, const rclcpp::Duration &dt);
24+
void write(const rclcpp::Time& t, const rclcpp::Duration& dt);
2525

2626
private:
2727
rclcpp::Node::SharedPtr nh_;

src/bitbots_lowlevel/bitbots_ros_control/include/bitbots_ros_control/button_hardware_interface.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -16,12 +16,12 @@ namespace bitbots_ros_control {
1616

1717
class ButtonHardwareInterface : public bitbots_ros_control::HardwareInterface {
1818
public:
19-
explicit ButtonHardwareInterface(rclcpp::Node::SharedPtr nh, std::shared_ptr<DynamixelDriver> &driver, int id,
19+
explicit ButtonHardwareInterface(rclcpp::Node::SharedPtr nh, std::shared_ptr<DynamixelDriver>& driver, int id,
2020
std::string topic, int read_rate_);
2121

2222
bool init();
23-
void read(const rclcpp::Time &t, const rclcpp::Duration &dt);
24-
void write(const rclcpp::Time &t, const rclcpp::Duration &dt);
23+
void read(const rclcpp::Time& t, const rclcpp::Duration& dt);
24+
void write(const rclcpp::Time& t, const rclcpp::Duration& dt);
2525

2626
private:
2727
rclcpp::Node::SharedPtr nh_;

src/bitbots_lowlevel/bitbots_ros_control/include/bitbots_ros_control/core_hardware_interface.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -18,16 +18,16 @@ namespace bitbots_ros_control {
1818

1919
class CoreHardwareInterface : public bitbots_ros_control::HardwareInterface {
2020
public:
21-
explicit CoreHardwareInterface(rclcpp::Node::SharedPtr nh, std::shared_ptr<DynamixelDriver> &driver, int id,
21+
explicit CoreHardwareInterface(rclcpp::Node::SharedPtr nh, std::shared_ptr<DynamixelDriver>& driver, int id,
2222
int read_rate);
2323

2424
bool get_power_status();
2525

2626
bool init();
2727

28-
void read(const rclcpp::Time &t, const rclcpp::Duration &dt);
28+
void read(const rclcpp::Time& t, const rclcpp::Duration& dt);
2929

30-
void write(const rclcpp::Time &t, const rclcpp::Duration &dt);
30+
void write(const rclcpp::Time& t, const rclcpp::Duration& dt);
3131
void restoreAfterPowerCycle();
3232

3333
private:

src/bitbots_lowlevel/bitbots_ros_control/include/bitbots_ros_control/dynamixel_servo_hardware_interface.hpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,7 @@
1919

2020
namespace bitbots_ros_control {
2121
template <typename T>
22-
std::string vecToString(const std::vector<T> &vec) {
22+
std::string vecToString(const std::vector<T>& vec) {
2323
std::stringstream ss;
2424
ss << "[";
2525
for (unsigned int i = 0; i < vec.size(); ++i) {
@@ -50,8 +50,8 @@ class DynamixelServoHardwareInterface : public bitbots_ros_control::HardwareInte
5050
explicit DynamixelServoHardwareInterface(rclcpp::Node::SharedPtr nh);
5151

5252
bool init();
53-
void read(const rclcpp::Time &t, const rclcpp::Duration &dt);
54-
void write(const rclcpp::Time &t, const rclcpp::Duration &dt);
53+
void read(const rclcpp::Time& t, const rclcpp::Duration& dt);
54+
void write(const rclcpp::Time& t, const rclcpp::Duration& dt);
5555
void addBusInterface(std::shared_ptr<ServoBusInterface> bus);
5656
void writeROMRAM(bool first_time);
5757

@@ -61,7 +61,7 @@ class DynamixelServoHardwareInterface : public bitbots_ros_control::HardwareInte
6161

6262
void setTorqueCb(std_msgs::msg::Bool::SharedPtr enabled);
6363
void individualTorqueCb(bitbots_msgs::msg::JointTorque msg);
64-
void commandCb(const bitbots_msgs::msg::JointCommand &command_msg);
64+
void commandCb(const bitbots_msgs::msg::JointCommand& command_msg);
6565

6666
std::vector<int32_t> goal_torque_individual_;
6767

src/bitbots_lowlevel/bitbots_ros_control/include/bitbots_ros_control/hardware_interface.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -12,13 +12,13 @@ class HardwareInterface {
1212
public:
1313
virtual bool init() = 0;
1414

15-
virtual void read(const rclcpp::Time &t, const rclcpp::Duration &dt) {};
15+
virtual void read(const rclcpp::Time& t, const rclcpp::Duration& dt) {};
1616

17-
virtual void write(const rclcpp::Time &t, const rclcpp::Duration &dt) {};
17+
virtual void write(const rclcpp::Time& t, const rclcpp::Duration& dt) {};
1818

1919
virtual void restoreAfterPowerCycle() {};
2020

21-
virtual ~HardwareInterface(){};
21+
virtual ~HardwareInterface() {};
2222
};
2323
} // namespace bitbots_ros_control
2424
#endif // BITBOTS_ROS_CONTROL_INCLUDE_BITBOTS_ROS_CONTROL_HARDWARE_INTERFACE_H_

src/bitbots_lowlevel/bitbots_ros_control/include/bitbots_ros_control/imu_hardware_interface.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -19,12 +19,12 @@ namespace bitbots_ros_control {
1919

2020
class ImuHardwareInterface : public bitbots_ros_control::HardwareInterface {
2121
public:
22-
explicit ImuHardwareInterface(rclcpp::Node::SharedPtr nh, std::shared_ptr<DynamixelDriver> &driver, int id,
22+
explicit ImuHardwareInterface(rclcpp::Node::SharedPtr nh, std::shared_ptr<DynamixelDriver>& driver, int id,
2323
std::string topic, std::string frame, std::string name);
2424

2525
bool init();
26-
void read(const rclcpp::Time &t, const rclcpp::Duration &dt);
27-
void write(const rclcpp::Time &t, const rclcpp::Duration &dt);
26+
void read(const rclcpp::Time& t, const rclcpp::Duration& dt);
27+
void write(const rclcpp::Time& t, const rclcpp::Duration& dt);
2828
void restoreAfterPowerCycle();
2929

3030
private:

src/bitbots_lowlevel/bitbots_ros_control/include/bitbots_ros_control/leds_hardware_interface.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -12,12 +12,12 @@ namespace bitbots_ros_control {
1212

1313
class LedsHardwareInterface : public bitbots_ros_control::HardwareInterface {
1414
public:
15-
LedsHardwareInterface(rclcpp::Node::SharedPtr nh, std::shared_ptr<DynamixelDriver> &driver, uint8_t id,
15+
LedsHardwareInterface(rclcpp::Node::SharedPtr nh, std::shared_ptr<DynamixelDriver>& driver, uint8_t id,
1616
uint8_t num_leds, uint8_t start_number);
1717

1818
bool init();
19-
void read(const rclcpp::Time &t, const rclcpp::Duration &dt);
20-
void write(const rclcpp::Time &t, const rclcpp::Duration &dt);
19+
void read(const rclcpp::Time& t, const rclcpp::Duration& dt);
20+
void write(const rclcpp::Time& t, const rclcpp::Duration& dt);
2121

2222
private:
2323
rclcpp::Node::SharedPtr nh_;

src/bitbots_lowlevel/bitbots_ros_control/include/bitbots_ros_control/servo_bus_interface.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -21,11 +21,11 @@ namespace bitbots_ros_control {
2121

2222
class ServoBusInterface : public bitbots_ros_control::HardwareInterface {
2323
public:
24-
explicit ServoBusInterface(rclcpp::Node::SharedPtr nh, std::shared_ptr<DynamixelDriver> &driver,
24+
explicit ServoBusInterface(rclcpp::Node::SharedPtr nh, std::shared_ptr<DynamixelDriver>& driver,
2525
std::vector<std::tuple<int, std::string, float, float, std::string>> servos);
2626
bool init();
27-
void read(const rclcpp::Time &t, const rclcpp::Duration &dt);
28-
void write(const rclcpp::Time &t, const rclcpp::Duration &dt);
27+
void read(const rclcpp::Time& t, const rclcpp::Duration& dt);
28+
void write(const rclcpp::Time& t, const rclcpp::Duration& dt);
2929
void restoreAfterPowerCycle();
3030

3131
bool loadDynamixels();

src/bitbots_lowlevel/bitbots_ros_control/include/bitbots_ros_control/wolfgang_hardware_interface.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -21,9 +21,9 @@ class WolfgangHardwareInterface {
2121

2222
bool init();
2323

24-
void read(const rclcpp::Time &t, const rclcpp::Duration &dt);
24+
void read(const rclcpp::Time& t, const rclcpp::Duration& dt);
2525

26-
void write(const rclcpp::Time &t, const rclcpp::Duration &dt);
26+
void write(const rclcpp::Time& t, const rclcpp::Duration& dt);
2727

2828
private:
2929
bool create_interfaces(std::vector<std::pair<std::string, int>> dxl_devices);

src/bitbots_lowlevel/bitbots_ros_control/src/bitfoot_hardware_interface.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@
33

44
namespace bitbots_ros_control {
55

6-
BitFootHardwareInterface::BitFootHardwareInterface(rclcpp::Node::SharedPtr nh, std::shared_ptr<DynamixelDriver> &driver,
6+
BitFootHardwareInterface::BitFootHardwareInterface(rclcpp::Node::SharedPtr nh, std::shared_ptr<DynamixelDriver>& driver,
77
int id, std::string topic_name, std::string name) {
88
nh_ = nh;
99
driver_ = driver;
@@ -19,7 +19,7 @@ bool BitFootHardwareInterface::init() {
1919
return true;
2020
}
2121

22-
void BitFootHardwareInterface::read(const rclcpp::Time &t, const rclcpp::Duration &dt) {
22+
void BitFootHardwareInterface::read(const rclcpp::Time& t, const rclcpp::Duration& dt) {
2323
/**
2424
* Reads the foot pressure sensors of the BitFoot
2525
*/
@@ -101,7 +101,7 @@ void BitFootHardwareInterface::read(const rclcpp::Time &t, const rclcpp::Duratio
101101
}
102102
std::vector<diagnostic_msgs::msg::KeyValue> keyValues = std::vector<diagnostic_msgs::msg::KeyValue>();
103103
// iterate through map and save it into values
104-
for (auto const &ent1 : map) {
104+
for (auto const& ent1 : map) {
105105
diagnostic_msgs::msg::KeyValue key_value = diagnostic_msgs::msg::KeyValue();
106106
key_value.key = ent1.first;
107107
key_value.value = ent1.second;
@@ -115,5 +115,5 @@ void BitFootHardwareInterface::read(const rclcpp::Time &t, const rclcpp::Duratio
115115
}
116116

117117
// we dont write anything to the pressure sensors
118-
void BitFootHardwareInterface::write(const rclcpp::Time &t, const rclcpp::Duration &dt) {}
118+
void BitFootHardwareInterface::write(const rclcpp::Time& t, const rclcpp::Duration& dt) {}
119119
} // namespace bitbots_ros_control

0 commit comments

Comments
 (0)