Skip to content

Commit

Permalink
apply clang-tidy
Browse files Browse the repository at this point in the history
  • Loading branch information
Alpaca-zip committed Sep 9, 2023
1 parent a574fb4 commit 9eecb1c
Show file tree
Hide file tree
Showing 12 changed files with 94 additions and 101 deletions.
4 changes: 2 additions & 2 deletions include/dynamixel_control.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@
#define RF_LEG_UPPER_ID 1
#define RF_LEG_LOWER_ID 13

class dynamixelControl
class DynamixelControl
{
private:
ros::NodeHandle _nh;
Expand All @@ -60,7 +60,7 @@ class dynamixelControl
DynamixelWorkbench _dxl_wb;

public:
dynamixelControl();
DynamixelControl();
void controlLoop();
void monitorLFLegCallback(const trajectory_msgs::JointTrajectory& LF_leg);
void monitorLRLegCallback(const trajectory_msgs::JointTrajectory& LR_leg);
Expand Down
4 changes: 2 additions & 2 deletions include/inverse_kinematics.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
#define BONE_LENGTH 83.0
#define LENGTH 21.0

class inverseKinematics
class InverseKinematics
{
private:
ros::NodeHandle _nh;
Expand All @@ -38,6 +38,6 @@ class inverseKinematics
double _duration;

public:
inverseKinematics();
InverseKinematics();
void inverseKinematicsCallback(const std_msgs::Float64MultiArray& leg_position);
};
4 changes: 2 additions & 2 deletions include/key_control.h
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@
#include <std_msgs/Float64.h>
#include <termios.h>

class keyControl
class KeyControl
{
private:
ros::NodeHandle _nh;
Expand All @@ -35,7 +35,7 @@ class keyControl
std_msgs::Bool _stand;

public:
keyControl();
KeyControl();
void controlLoop();
int getch();
};
4 changes: 2 additions & 2 deletions include/posture_stabilization.h
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@
#define X_OFFSET 61
#define Y_OFFSET 94

class postureStabilization
class PostureStabilization
{
private:
ros::NodeHandle _nh;
Expand Down Expand Up @@ -57,7 +57,7 @@ class postureStabilization
double _roll_sum, _pitch_sum;

public:
postureStabilization();
PostureStabilization();
void controlLoop();
void imuCallback(const sensor_msgs::Imu& msg);
void quatToRPY(const geometry_msgs::Quaternion quat, double& roll, double& pitch, double& yaw);
Expand Down
4 changes: 2 additions & 2 deletions include/standing_motion.h
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@
#include <std_msgs/Bool.h>
#include <std_msgs/Float64MultiArray.h>

class standingMotion
class StandingMotion
{
private:
ros::NodeHandle _nh;
Expand All @@ -34,6 +34,6 @@ class standingMotion
double _x_offset, _z_offset_LF_leg, _z_offset_LR_leg, _z_offset_RR_leg, _z_offset_RF_leg;

public:
standingMotion();
StandingMotion();
void standingMotionCallback(const std_msgs::Bool& stand);
};
4 changes: 2 additions & 2 deletions include/trot_gait.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
#include <std_msgs/Float64.h>
#include <std_msgs/Float64MultiArray.h>

class trotGait
class TrotGait
{
private:
ros::NodeHandle _nh;
Expand All @@ -44,7 +44,7 @@ class trotGait
double _c[4], _c_inv[4], _c_iter[4], _l_inv[4][2];

public:
trotGait();
TrotGait();
void controlLoop();
void trotFowardMotionCallback(const std_msgs::Float64& direction_x);
void trotTurnMotionCallback(const std_msgs::Float64& turn);
Expand Down
48 changes: 24 additions & 24 deletions src/dynamixel_control.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@

#include "dynamixel_control.h"

dynamixelControl::dynamixelControl() : _pnh("~")
DynamixelControl::DynamixelControl() : _pnh("~")
{
_pnh.param<std::string>("port", _port_name_str, "/dev/ttyACM1");
_pnh.param<int>("model_number", _model_number_int, 12);
Expand Down Expand Up @@ -44,10 +44,10 @@ dynamixelControl::dynamixelControl() : _pnh("~")
_dxl_id[11] = RF_LEG_LOWER_ID;
}

_sub_LF_leg = _nh.subscribe("leftfront_leg_controller/command", 10, &dynamixelControl::monitorLFLegCallback, this);
_sub_LR_leg = _nh.subscribe("leftback_leg_controller/command", 10, &dynamixelControl::monitorLRLegCallback, this);
_sub_RR_leg = _nh.subscribe("rightback_leg_controller/command", 10, &dynamixelControl::monitorRRLegCallback, this);
_sub_RF_leg = _nh.subscribe("rightfront_leg_controller/command", 10, &dynamixelControl::monitorRFLegCallback, this);
_sub_LF_leg = _nh.subscribe("leftfront_leg_controller/command", 10, &DynamixelControl::monitorLFLegCallback, this);
_sub_LR_leg = _nh.subscribe("leftback_leg_controller/command", 10, &DynamixelControl::monitorLRLegCallback, this);
_sub_RR_leg = _nh.subscribe("rightback_leg_controller/command", 10, &DynamixelControl::monitorRRLegCallback, this);
_sub_RF_leg = _nh.subscribe("rightfront_leg_controller/command", 10, &DynamixelControl::monitorRFLegCallback, this);

_joint_pos[0].data = 0; // LF_leg_shoulder_joint
_joint_pos[1].data = 1.5; // LF_leg_upper_joint
Expand All @@ -70,39 +70,39 @@ dynamixelControl::dynamixelControl() : _pnh("~")
dxlAddSyncWriteHandler();
}

void dynamixelControl::monitorLFLegCallback(const trajectory_msgs::JointTrajectory& LF_leg)
void DynamixelControl::monitorLFLegCallback(const trajectory_msgs::JointTrajectory& LF_leg)
{
for (int i = 0; i < 3; i++)
{
_joint_pos[i].data = LF_leg.points[0].positions[i];
}
}

void dynamixelControl::monitorLRLegCallback(const trajectory_msgs::JointTrajectory& LR_leg)
void DynamixelControl::monitorLRLegCallback(const trajectory_msgs::JointTrajectory& LR_leg)
{
for (int i = 3; i < 6; i++)
{
_joint_pos[i].data = LR_leg.points[0].positions[i - 3];
}
}

void dynamixelControl::monitorRRLegCallback(const trajectory_msgs::JointTrajectory& RR_leg)
void DynamixelControl::monitorRRLegCallback(const trajectory_msgs::JointTrajectory& RR_leg)
{
for (int i = 6; i < 9; i++)
{
_joint_pos[i].data = RR_leg.points[0].positions[i - 6];
}
}

void dynamixelControl::monitorRFLegCallback(const trajectory_msgs::JointTrajectory& RF_leg)
void DynamixelControl::monitorRFLegCallback(const trajectory_msgs::JointTrajectory& RF_leg)
{
for (int i = 9; i < 12; i++)
{
_joint_pos[i].data = RF_leg.points[0].positions[i - 9];
}
}

void dynamixelControl::controlLoop()
void DynamixelControl::controlLoop()
{
int32_t goal_position[12];
const uint8_t handler_index = 0;
Expand All @@ -111,17 +111,17 @@ void dynamixelControl::controlLoop()
goal_position[i] = 512 + 3.41 * 180 * (_joint_pos[i].data / M_PI);
}
_result = _dxl_wb.syncWrite(handler_index, &goal_position[0], &_log);
if (_result == false)
if (!_result)
{
ROS_ERROR("%s", _log);
ROS_ERROR("Failed to sync write position");
}
}

void dynamixelControl::dxlInit()
void DynamixelControl::dxlInit()
{
_result = _dxl_wb.init(_port_name, _baudrate, &_log);
if (_result == false)
if (!_result)
{
ROS_ERROR("%s", _log);
ROS_ERROR("Failed to init");
Expand All @@ -130,31 +130,31 @@ void dynamixelControl::dxlInit()
ROS_WARN("Succeed to init(%d)", _baudrate);
}

void dynamixelControl::dxlTorqueOn()
void DynamixelControl::dxlTorqueOn()
{
for (int cnt = 0; cnt < 12; cnt++)
for (unsigned char cnt : _dxl_id)
{
_result = _dxl_wb.ping(_dxl_id[cnt], &_model_number, &_log);
if (_result == false)
_result = _dxl_wb.ping(cnt, &_model_number, &_log);
if (!_result)
{
ROS_ERROR("%s", _log);
ROS_ERROR("Failed to ping");
}
else
{
ROS_WARN("Succeeded to ping");
ROS_WARN("id : %d, model_number : %d", _dxl_id[cnt], _model_number);
ROS_WARN("id : %d, model_number : %d", cnt, _model_number);
}
_result = _dxl_wb.torqueOn(_dxl_id[cnt]);
if (_result == false)
_result = _dxl_wb.torqueOn(cnt);
if (!_result)
ROS_ERROR("torqueOn ERROR");
}
}

void dynamixelControl::dxlAddSyncWriteHandler()
void DynamixelControl::dxlAddSyncWriteHandler()
{
_result = _dxl_wb.addSyncWriteHandler(_dxl_id[0], "Goal_Position", &_log);
if (_result == false)
if (!_result)
{
ROS_ERROR("%s", _log);
ROS_ERROR("Failed to add sync write handler");
Expand All @@ -164,11 +164,11 @@ void dynamixelControl::dxlAddSyncWriteHandler()
int main(int argc, char** argv)
{
ros::init(argc, argv, "dynamixel_control");
dynamixelControl DC;
DynamixelControl dc;
ros::Rate loop_rate(100);
while (ros::ok())
{
DC.controlLoop();
dc.controlLoop();
ros::spinOnce();
loop_rate.sleep();
}
Expand Down
44 changes: 22 additions & 22 deletions src/inverse_kinematics.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,15 +16,15 @@

#include "inverse_kinematics.h"

inverseKinematics::inverseKinematics() : _pnh("~")
InverseKinematics::InverseKinematics() : _pnh("~")
{
_pnh.param<double>("duration", _duration, 0.01);

_pub_LF_leg = _nh.advertise<trajectory_msgs::JointTrajectory>("leftfront_leg_controller/command", 10);
_pub_LR_leg = _nh.advertise<trajectory_msgs::JointTrajectory>("leftback_leg_controller/command", 10);
_pub_RF_leg = _nh.advertise<trajectory_msgs::JointTrajectory>("rightfront_leg_controller/command", 10);
_pub_RR_leg = _nh.advertise<trajectory_msgs::JointTrajectory>("rightback_leg_controller/command", 10);
_sub_leg_position = _nh.subscribe("leg_position", 10, &inverseKinematics::inverseKinematicsCallback, this);
_sub_leg_position = _nh.subscribe("leg_position", 10, &InverseKinematics::inverseKinematicsCallback, this);

_LF_leg.joint_names.resize(3);
_LF_leg.points.resize(1);
Expand Down Expand Up @@ -52,12 +52,12 @@ inverseKinematics::inverseKinematics() : _pnh("~")
_RF_leg.joint_names[2] = "rightfront_leg_lower_joint";
}

void inverseKinematics::inverseKinematicsCallback(const std_msgs::Float64MultiArray& leg_position)
void InverseKinematics::inverseKinematicsCallback(const std_msgs::Float64MultiArray& leg_position)
{
double x, y, z, a0, a1, b0;
double angle1, angle2, angle3;
double target_leg_shoulder_joint, target_L_leg_upper_joint, target_L_leg_lower_joint, target_R_leg_upper_joint,
target_R_leg_lower_joint;
double target_leg_shoulder_joint, target_l_leg_upper_joint, target_l_leg_lower_joint, target_r_leg_upper_joint,
target_r_leg_lower_joint;

for (int l = 0; l < 4; l++)
{
Expand All @@ -74,11 +74,11 @@ void inverseKinematics::inverseKinematicsCallback(const std_msgs::Float64MultiAr
angle2 = atan2(x, sqrt(y * y + z * z - LENGTH * LENGTH)) -
atan2(BONE_LENGTH * sin(angle3), BONE_LENGTH * (1 + cos(angle3)));
target_leg_shoulder_joint = angle1;
target_L_leg_upper_joint = -angle2;
target_L_leg_lower_joint = angle3;
target_l_leg_upper_joint = -angle2;
target_l_leg_lower_joint = angle3;
_LF_leg.points[0].positions[0] = target_leg_shoulder_joint;
_LF_leg.points[0].positions[1] = target_L_leg_upper_joint;
_LF_leg.points[0].positions[2] = target_L_leg_lower_joint;
_LF_leg.points[0].positions[1] = target_l_leg_upper_joint;
_LF_leg.points[0].positions[2] = target_l_leg_lower_joint;
_LF_leg.header.stamp = ros::Time::now();
_LF_leg.points[0].time_from_start = ros::Duration(_duration);
_pub_LF_leg.publish(_LF_leg);
Expand All @@ -90,11 +90,11 @@ void inverseKinematics::inverseKinematicsCallback(const std_msgs::Float64MultiAr
angle2 = atan2(x, sqrt(y * y + z * z - LENGTH * LENGTH)) -
atan2(BONE_LENGTH * sin(angle3), BONE_LENGTH * (1 + cos(angle3)));
target_leg_shoulder_joint = angle1;
target_L_leg_upper_joint = -angle2;
target_L_leg_lower_joint = angle3;
target_l_leg_upper_joint = -angle2;
target_l_leg_lower_joint = angle3;
_LR_leg.points[0].positions[0] = target_leg_shoulder_joint;
_LR_leg.points[0].positions[1] = target_L_leg_upper_joint;
_LR_leg.points[0].positions[2] = target_L_leg_lower_joint;
_LR_leg.points[0].positions[1] = target_l_leg_upper_joint;
_LR_leg.points[0].positions[2] = target_l_leg_lower_joint;
_LR_leg.header.stamp = ros::Time::now();
_LR_leg.points[0].time_from_start = ros::Duration(_duration);
_pub_LR_leg.publish(_LR_leg);
Expand All @@ -106,11 +106,11 @@ void inverseKinematics::inverseKinematicsCallback(const std_msgs::Float64MultiAr
angle2 = atan2(x, sqrt(y * y + z * z - LENGTH * LENGTH)) -
atan2(BONE_LENGTH * sin(angle3), BONE_LENGTH * (1 + cos(angle3)));
target_leg_shoulder_joint = angle1;
target_R_leg_upper_joint = angle2;
target_R_leg_lower_joint = -angle3;
target_r_leg_upper_joint = angle2;
target_r_leg_lower_joint = -angle3;
_RR_leg.points[0].positions[0] = target_leg_shoulder_joint;
_RR_leg.points[0].positions[1] = target_R_leg_upper_joint;
_RR_leg.points[0].positions[2] = target_R_leg_lower_joint;
_RR_leg.points[0].positions[1] = target_r_leg_upper_joint;
_RR_leg.points[0].positions[2] = target_r_leg_lower_joint;
_RR_leg.header.stamp = ros::Time::now();
_RR_leg.points[0].time_from_start = ros::Duration(_duration);
_pub_RR_leg.publish(_RR_leg);
Expand All @@ -122,11 +122,11 @@ void inverseKinematics::inverseKinematicsCallback(const std_msgs::Float64MultiAr
angle2 = atan2(x, sqrt(y * y + z * z - LENGTH * LENGTH)) -
atan2(BONE_LENGTH * sin(angle3), BONE_LENGTH * (1 + cos(angle3)));
target_leg_shoulder_joint = angle1;
target_R_leg_upper_joint = angle2;
target_R_leg_lower_joint = -angle3;
target_r_leg_upper_joint = angle2;
target_r_leg_lower_joint = -angle3;
_RF_leg.points[0].positions[0] = target_leg_shoulder_joint;
_RF_leg.points[0].positions[1] = target_R_leg_upper_joint;
_RF_leg.points[0].positions[2] = target_R_leg_lower_joint;
_RF_leg.points[0].positions[1] = target_r_leg_upper_joint;
_RF_leg.points[0].positions[2] = target_r_leg_lower_joint;
_RF_leg.header.stamp = ros::Time::now();
_RF_leg.points[0].time_from_start = ros::Duration(_duration);
_pub_RF_leg.publish(_RF_leg);
Expand All @@ -137,7 +137,7 @@ void inverseKinematics::inverseKinematicsCallback(const std_msgs::Float64MultiAr
int main(int argc, char** argv)
{
ros::init(argc, argv, "inverse_kinematics");
inverseKinematics IK;
InverseKinematics ik;
ros::spin();
return 0;
}
10 changes: 5 additions & 5 deletions src/key_control.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@

#include "key_control.h"

keyControl::keyControl()
KeyControl::KeyControl()
{
_trot_foward_motion_pub = _nh.advertise<std_msgs::Float64>("trot_foward_motion", 10);
_trot_turn_motion_pub = _nh.advertise<std_msgs::Float64>("trot_turn_motion", 10);
Expand All @@ -41,7 +41,7 @@ keyControl::keyControl()
std::cout << "\033[32mX : Posture control on/off\033[0m" << std::endl;
}

int keyControl::getch()
int KeyControl::getch()
{
static struct termios oldt, newt;
tcgetattr(STDIN_FILENO, &oldt);
Expand All @@ -53,7 +53,7 @@ int keyControl::getch()
return c;
}

void keyControl::controlLoop()
void KeyControl::controlLoop()
{
int c = getch();
if (c == 'w')
Expand Down Expand Up @@ -129,11 +129,11 @@ void keyControl::controlLoop()
int main(int argc, char** argv)
{
ros::init(argc, argv, "key_control");
keyControl KC;
KeyControl kc;
ros::Rate loop_rate(10);
while (ros::ok())
{
KC.controlLoop();
kc.controlLoop();
ros::spinOnce();
loop_rate.sleep();
}
Expand Down
Loading

0 comments on commit 9eecb1c

Please sign in to comment.