Skip to content

Commit 728f7f1

Browse files
committed
Fixed lint
Signed-off-by: Sungho Woo <[email protected]>
1 parent d74c357 commit 728f7f1

File tree

5 files changed

+45
-34
lines changed

5 files changed

+45
-34
lines changed

include/dynamixel_hardware_interface/dynamixel/dynamixel.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -77,7 +77,7 @@ typedef struct
7777
uint16_t indirect_data_addr; ///< Base address for indirect data.
7878
uint16_t cnt; ///< Number of control items.
7979
uint8_t size; ///< Total size in bytes.
80-
std::vector<std::string> item_name; ///< Names of the control items.
80+
std::vector<std::string> item_name; ///< Names of the control items.
8181
std::vector<uint8_t> item_size; ///< Sizes of each control item in bytes.
8282
} IndirectInfo;
8383

@@ -103,7 +103,7 @@ typedef struct
103103
std::vector<std::string> item_name; ///< List of control item names.
104104
std::vector<uint8_t> item_size; ///< Sizes of the control items.
105105
std::vector<uint16_t> item_addr; ///< Addresses of the control items.
106-
std::vector<std::shared_ptr<double>> item_data_ptr_vec; ///< Pointers to the data.
106+
std::vector<std::shared_ptr<double>> item_data_ptr_vec; ///< Pointers to the data.
107107
} RWItemList;
108108

109109
class Dynamixel

include/dynamixel_hardware_interface/dynamixel/dynamixel_info.hpp

Lines changed: 7 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -18,14 +18,16 @@
1818
#ifndef DYNAMIXEL_HARDWARE_INTERFACE__DYNAMIXEL__DYNAMIXEL_INFO_HPP_
1919
#define DYNAMIXEL_HARDWARE_INTERFACE__DYNAMIXEL__DYNAMIXEL_INFO_HPP_
2020

21-
#include <boost/algorithm/string.hpp>
21+
#include <cmath>
22+
#include <cstring>
23+
2224
#include <fstream>
2325
#include <iostream>
24-
#include <vector>
25-
#include <cstring>
26-
#include <string>
2726
#include <map>
28-
#include <cmath>
27+
#include <string>
28+
#include <vector>
29+
30+
#include <boost/algorithm/string.hpp>
2931

3032
namespace dynamixel_hardware_interface
3133
{

include/dynamixel_hardware_interface/dynamixel_hardware_interface.hpp

Lines changed: 7 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -65,7 +65,7 @@ typedef struct HandlerVarType_
6565
uint8_t id; /**< ID of the Dynamixel component. */
6666
std::string name; /**< Name of the component. */
6767
std::vector<std::string> interface_name_vec; /**< Vector of interface names. */
68-
std::vector<std::shared_ptr<double>> value_ptr_vec; /**< Vector of pointers to interface values. */
68+
std::vector<std::shared_ptr<double>> value_ptr_vec; /**< Vector interface values. */
6969
} HandlerVarType;
7070

7171
/**
@@ -117,7 +117,8 @@ class DynamixelHardware : public
117117
* @return Callback return indicating success or error.
118118
*/
119119
DYNAMIXEL_HARDWARE_INTERFACE_PUBLIC
120-
hardware_interface::CallbackReturn on_init(const hardware_interface::HardwareInfo & info) override;
120+
hardware_interface::CallbackReturn on_init(const hardware_interface::HardwareInfo & info)
121+
override;
121122

122123
/**
123124
* @brief Exports state interfaces for ROS2.
@@ -139,15 +140,17 @@ class DynamixelHardware : public
139140
* @return Callback return indicating success or error.
140141
*/
141142
DYNAMIXEL_HARDWARE_INTERFACE_PUBLIC
142-
hardware_interface::CallbackReturn on_activate(const rclcpp_lifecycle::State & previous_state) override;
143+
hardware_interface::CallbackReturn on_activate(const rclcpp_lifecycle::State & previous_state)
144+
override;
143145

144146
/**
145147
* @brief Callback for deactivating the hardware interface.
146148
* @param previous_state Previous lifecycle state.
147149
* @return Callback return indicating success or error.
148150
*/
149151
DYNAMIXEL_HARDWARE_INTERFACE_PUBLIC
150-
hardware_interface::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & previous_state) override;
152+
hardware_interface::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & previous_state)
153+
override;
151154

152155
/**
153156
* @brief Reads data from the hardware.

src/dynamixel/dynamixel.cpp

Lines changed: 11 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -661,15 +661,16 @@ bool Dynamixel::checkReadType()
661661
// Check if Indirect Data Read address and size are different
662662
uint16_t indirect_addr[2]; // [i-1], [i]
663663
uint8_t indirect_size[2]; // [i-1], [i]
664-
664+
665665
if (!dxl_info_.GetDxlControlItem(
666-
read_data_list_.at(dxl_index).id, "Indirect Data Read", indirect_addr[1], indirect_size[1]) ||
666+
read_data_list_.at(dxl_index).id, "Indirect Data Read", indirect_addr[1],
667+
indirect_size[1]) ||
667668
!dxl_info_.GetDxlControlItem(
668-
read_data_list_.at(dxl_index - 1).id, "Indirect Data Read", indirect_addr[0], indirect_size[0]))
669+
read_data_list_.at(dxl_index - 1).id, "Indirect Data Read", indirect_addr[0],
670+
indirect_size[0]))
669671
{
670672
return BULK;
671673
}
672-
673674
if (indirect_addr[1] != indirect_addr[0] || indirect_size[1] != indirect_size[0]) {
674675
return BULK;
675676
}
@@ -683,7 +684,7 @@ bool Dynamixel::checkReadType()
683684
item_index++)
684685
{
685686
if (read_data_list_.at(dxl_index).item_name.at(item_index) !=
686-
read_data_list_.at(dxl_index - 1).item_name.at(item_index) ||
687+
read_data_list_.at(dxl_index - 1).item_name.at(item_index) ||
687688
read_data_list_.at(dxl_index).item_addr.at(item_index) !=
688689
read_data_list_.at(dxl_index - 1).item_addr.at(item_index) ||
689690
read_data_list_.at(dxl_index).item_size.at(item_index) !=
@@ -702,15 +703,15 @@ bool Dynamixel::checkWriteType()
702703
// Check if Indirect Data Write address and size are different
703704
uint16_t indirect_addr[2]; // [i-1], [i]
704705
uint8_t indirect_size[2]; // [i-1], [i]
705-
706706
if (!dxl_info_.GetDxlControlItem(
707-
write_data_list_.at(dxl_index).id, "Indirect Data Write", indirect_addr[1], indirect_size[1]) ||
707+
write_data_list_.at(dxl_index).id, "Indirect Data Write", indirect_addr[1],
708+
indirect_size[1]) ||
708709
!dxl_info_.GetDxlControlItem(
709-
write_data_list_.at(dxl_index - 1).id, "Indirect Data Write", indirect_addr[0], indirect_size[0]))
710+
write_data_list_.at(dxl_index - 1).id, "Indirect Data Write", indirect_addr[0],
711+
indirect_size[0]))
710712
{
711713
return BULK;
712714
}
713-
714715
if (indirect_addr[1] != indirect_addr[0] || indirect_size[1] != indirect_size[0]) {
715716
return BULK;
716717
}
@@ -728,8 +729,7 @@ bool Dynamixel::checkWriteType()
728729
write_data_list_.at(dxl_index).item_addr.at(item_index) !=
729730
write_data_list_.at(dxl_index - 1).item_addr.at(item_index) ||
730731
write_data_list_.at(dxl_index).item_size.at(item_index) !=
731-
write_data_list_.at(dxl_index - 1).item_size.at(item_index)
732-
)
732+
write_data_list_.at(dxl_index - 1).item_size.at(item_index))
733733
{
734734
return BULK;
735735
}

src/dynamixel_hardware_interface.cpp

Lines changed: 18 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -51,7 +51,9 @@ DynamixelHardware::~DynamixelHardware()
5151
hardware_interface::CallbackReturn DynamixelHardware::on_init(
5252
const hardware_interface::HardwareInfo & info)
5353
{
54-
if (hardware_interface::SystemInterface::on_init(info) != hardware_interface::CallbackReturn::SUCCESS) {
54+
if (hardware_interface::SystemInterface::on_init(info) !=
55+
hardware_interface::CallbackReturn::SUCCESS)
56+
{
5557
RCLCPP_ERROR_STREAM(logger_, "Failed to initialize DynamixelHardware");
5658
return hardware_interface::CallbackReturn::ERROR;
5759
}
@@ -78,9 +80,11 @@ hardware_interface::CallbackReturn DynamixelHardware::on_init(
7880
RCLCPP_INFO_STREAM(logger_, "$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$");
7981
RCLCPP_INFO_STREAM(logger_, "$$$$$ Init Dxl Comm Port");
8082

81-
82-
if (info_.hardware_parameters.find("use_revolute_to_prismatic_gripper") != info_.hardware_parameters.end()) {
83-
use_revolute_to_prismatic_ = std::stoi(info_.hardware_parameters.at("use_revolute_to_prismatic_gripper")) != 0;
83+
if (info_.hardware_parameters.find("use_revolute_to_prismatic_gripper") !=
84+
info_.hardware_parameters.end())
85+
{
86+
use_revolute_to_prismatic_ =
87+
std::stoi(info_.hardware_parameters.at("use_revolute_to_prismatic_gripper")) != 0;
8488
}
8589

8690
if (use_revolute_to_prismatic_) {
@@ -383,7 +387,7 @@ hardware_interface::CallbackReturn DynamixelHardware::stop()
383387
}
384388

385389
hardware_interface::return_type DynamixelHardware::read(
386-
const rclcpp::Time & time, const rclcpp::Duration & period)
390+
const rclcpp::Time & time, const rclcpp::Duration & period)
387391
{
388392
if (dxl_status_ == REBOOTING) {
389393
RCLCPP_ERROR_STREAM(logger_, "Dynamixel Read Fail : REBOOTING");
@@ -426,14 +430,14 @@ hardware_interface::return_type DynamixelHardware::read(
426430
dxl_state_pub_uni_ptr_->unlockAndPublish();
427431
}
428432

429-
if (rclcpp::ok()) {
433+
if (rclcpp::ok()) {
430434
rclcpp::spin_some(this->get_node_base_interface());
431-
}
435+
}
432436
return hardware_interface::return_type::OK;
433437
}
434438

435439
hardware_interface::return_type DynamixelHardware::write(
436-
const rclcpp::Time & time, const rclcpp::Duration & period)
440+
const rclcpp::Time & time, const rclcpp::Duration & period)
437441
{
438442
if (dxl_status_ == DXL_OK || dxl_status_ == HW_ERROR) {
439443
dxl_comm_->WriteItemBuf();
@@ -551,7 +555,6 @@ bool DynamixelHardware::InitDxlItems()
551555
RCLCPP_INFO_STREAM(logger_, "$$$$$ Init Dxl Items");
552556
for (const hardware_interface::ComponentInfo & gpio : info_.gpios) {
553557
uint8_t id = static_cast<uint8_t>(stoi(gpio.parameters.at("ID")));
554-
555558
// First write items containing "Limit"
556559
for (auto it : gpio.parameters) {
557560
if (it.first != "ID" && it.first != "type" && it.first.find("Limit") != std::string::npos) {
@@ -599,7 +602,6 @@ bool DynamixelHardware::InitDxlReadItems()
599602
hdl_gpio_sensor_states_.clear();
600603
for (const hardware_interface::ComponentInfo & gpio : info_.gpios) {
601604
if (gpio.state_interfaces.size() && gpio.parameters.at("type") == "dxl") {
602-
603605
uint8_t id = static_cast<uint8_t>(stoi(gpio.parameters.at("ID")));
604606
HandlerVarType temp_read;
605607

@@ -982,11 +984,15 @@ void DynamixelHardware::set_dxl_torque_srv_callback(
982984

983985
void DynamixelHardware::initRevoluteToPrismaticParam()
984986
{
985-
if (info_.hardware_parameters.find("revolute_to_prismatic_dxl") != info_.hardware_parameters.end()) {
987+
if (info_.hardware_parameters.find("revolute_to_prismatic_dxl") !=
988+
info_.hardware_parameters.end())
989+
{
986990
conversion_dxl_name_ = info_.hardware_parameters.at("revolute_to_prismatic_dxl");
987991
}
988992

989-
if (info_.hardware_parameters.find("revolute_to_prismatic_joint") != info_.hardware_parameters.end()) {
993+
if (info_.hardware_parameters.find("revolute_to_prismatic_joint") !=
994+
info_.hardware_parameters.end())
995+
{
990996
conversion_joint_name_ = info_.hardware_parameters.at("revolute_to_prismatic_joint");
991997
}
992998

0 commit comments

Comments
 (0)