Skip to content

Commit

Permalink
Updated clang-format and added clang-tidy instructions
Browse files Browse the repository at this point in the history
  • Loading branch information
fmauch committed Apr 1, 2019
1 parent 5934612 commit 99533e4
Show file tree
Hide file tree
Showing 16 changed files with 133 additions and 105 deletions.
24 changes: 21 additions & 3 deletions .clang-format
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,8 @@ BreakConstructorInitializersBeforeComma: true
BinPackParameters: true
ColumnLimit: 120
ConstructorInitializerAllOnOneLineOrOnePerLine: true
DerivePointerBinding: true
DerivePointerBinding: false
PointerBindsToType: true
ExperimentalAutoDetectBinPacking: false
IndentCaseLabels: true
MaxEmptyLinesToKeep: 1
Expand All @@ -29,14 +30,12 @@ PenaltyBreakString: 1
PenaltyBreakFirstLessLess: 1000
PenaltyExcessCharacter: 1000
PenaltyReturnTypeOnItsOwnLine: 90
PointerBindsToType: false
SpacesBeforeTrailingComments: 2
Cpp11BracedListStyle: false
Standard: Auto
IndentWidth: 2
TabWidth: 2
UseTab: Never
BreakBeforeBraces: Allman
IndentFunctionDeclarationAfterType: false
SpacesInParentheses: false
SpacesInAngles: false
Expand All @@ -45,4 +44,23 @@ SpacesInCStyleCastParentheses: false
SpaceAfterControlStatementKeyword: true
SpaceBeforeAssignmentOperators: true
ContinuationIndentWidth: 4
SortIncludes: false
SpaceAfterCStyleCast: false

# Configure each individual brace in BraceWrapping
BreakBeforeBraces: Custom

# Control of individual brace wrapping cases
BraceWrapping: {
AfterClass: 'true'
AfterControlStatement: 'true'
AfterEnum : 'true'
AfterFunction : 'true'
AfterNamespace : 'true'
AfterStruct : 'true'
AfterUnion : 'true'
BeforeCatch : 'true'
BeforeElse : 'true'
IndentBraces : 'false'
}
...
10 changes: 10 additions & 0 deletions .clang-tidy
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
Checks: '-*,readability-identifier-naming'
CheckOptions:
- { key: readability-identifier-naming.NamespaceCase, value: lower_case }
- { key: readability-identifier-naming.ClassCase, value: CamelCase }
- { key: readability-identifier-naming.PrivateMemberSuffix, value: _ }
- { key: readability-identifier-naming.StructCase, value: CamelCase }
- { key: readability-identifier-naming.FunctionCase, value: camelBack }
- { key: readability-identifier-naming.VariableCase, value: lower_case }
- { key: readability-identifier-naming.GlobalVariablePrefix, value: g_ }
- { key: readability-identifier-naming.GlobalConstantCase, value: UPPER_CASE }
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ struct TrajectoryPoint
{
}

TrajectoryPoint(std::array<double, 6> &pos, std::array<double, 6> &vel, std::chrono::microseconds tfs)
TrajectoryPoint(std::array<double, 6>& pos, std::array<double, 6>& vel, std::chrono::microseconds tfs)
: positions(pos), velocities(vel), time_from_start(tfs)
{
}
Expand All @@ -46,7 +46,7 @@ class ActionTrajectoryFollowerInterface
{
public:
virtual bool start() = 0;
virtual bool execute(std::vector<TrajectoryPoint> &trajectory, std::atomic<bool> &interrupt) = 0;
virtual bool execute(std::vector<TrajectoryPoint>& trajectory, std::atomic<bool>& interrupt) = 0;
virtual void stop() = 0;
virtual ~ActionTrajectoryFollowerInterface(){};
};
18 changes: 9 additions & 9 deletions include/ur_rtde_driver/ros/hardware_interface.h
Original file line number Diff line number Diff line change
Expand Up @@ -49,8 +49,8 @@ class JointInterface : public hardware_interface::JointStateInterface
std::array<double, 6> velocities_, positions_, efforts_;

public:
JointInterface(std::vector<std::string> &joint_names);
void update(RTShared &packet);
JointInterface(std::vector<std::string>& joint_names);
void update(RTShared& packet);

typedef hardware_interface::JointStateInterface parent_type;
static const std::string INTERFACE_NAME;
Expand All @@ -62,21 +62,21 @@ class WrenchInterface : public hardware_interface::ForceTorqueSensorInterface

public:
WrenchInterface(std::string tcp_link);
void update(RTShared &packet);
void update(RTShared& packet);
typedef hardware_interface::ForceTorqueSensorInterface parent_type;
static const std::string INTERFACE_NAME;
};

class VelocityInterface : public HardwareInterface, public hardware_interface::VelocityJointInterface
{
private:
URCommander &commander_;
URCommander& commander_;
std::array<double, 6> velocity_cmd_, prev_velocity_cmd_;
double max_vel_change_;

public:
VelocityInterface(URCommander &commander, hardware_interface::JointStateInterface &js_interface,
std::vector<std::string> &joint_names, double max_vel_change);
VelocityInterface(URCommander& commander, hardware_interface::JointStateInterface& js_interface,
std::vector<std::string>& joint_names, double max_vel_change);
virtual bool write();
virtual void reset();
typedef hardware_interface::VelocityJointInterface parent_type;
Expand All @@ -86,12 +86,12 @@ class VelocityInterface : public HardwareInterface, public hardware_interface::V
class PositionInterface : public HardwareInterface, public hardware_interface::PositionJointInterface
{
private:
TrajectoryFollower &follower_;
TrajectoryFollower& follower_;
std::array<double, 6> position_cmd_;

public:
PositionInterface(TrajectoryFollower &follower, hardware_interface::JointStateInterface &js_interface,
std::vector<std::string> &joint_names);
PositionInterface(TrajectoryFollower& follower, hardware_interface::JointStateInterface& js_interface,
std::vector<std::string>& joint_names);
virtual bool write();
virtual void start();
virtual void stop();
Expand Down
8 changes: 4 additions & 4 deletions include/ur_rtde_driver/ros/lowbandwidth_trajectory_follower.h
Original file line number Diff line number Diff line change
Expand Up @@ -34,22 +34,22 @@ class LowBandwidthTrajectoryFollower : public ActionTrajectoryFollowerInterface
private:
std::atomic<bool> running_;
std::array<double, 6> last_positions_;
URCommander &commander_;
URCommander& commander_;
URServer server_;

double time_interval_, servoj_time_, servoj_time_waiting_, max_waiting_time_, servoj_gain_, servoj_lookahead_time_,
max_joint_difference_;

std::string program_;

bool execute(const std::array<double, 6> &positions, const std::array<double, 6> &velocities, double sample_number,
bool execute(const std::array<double, 6>& positions, const std::array<double, 6>& velocities, double sample_number,
double time_in_seconds);

public:
LowBandwidthTrajectoryFollower(URCommander &commander, std::string &reverse_ip, int reverse_port, bool version_3);
LowBandwidthTrajectoryFollower(URCommander& commander, std::string& reverse_ip, int reverse_port, bool version_3);

bool start();
bool execute(std::vector<TrajectoryPoint> &trajectory, std::atomic<bool> &interrupt);
bool execute(std::vector<TrajectoryPoint>& trajectory, std::atomic<bool>& interrupt);
void stop();

virtual ~LowBandwidthTrajectoryFollower(){};
Expand Down
12 changes: 6 additions & 6 deletions include/ur_rtde_driver/ros/trajectory_follower.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,29 +38,29 @@ class TrajectoryFollower : public ActionTrajectoryFollowerInterface
private:
std::atomic<bool> running_;
std::array<double, 6> last_positions_;
URCommander &commander_;
URCommander& commander_;
URServer server_;

double servoj_time_, servoj_lookahead_time_, servoj_gain_;
std::string program_;

template <typename T>
size_t append(uint8_t *buffer, T &val)
size_t append(uint8_t* buffer, T& val)
{
size_t s = sizeof(T);
std::memcpy(buffer, &val, s);
return s;
}

bool execute(std::array<double, 6> &positions, bool keep_alive);
bool execute(std::array<double, 6>& positions, bool keep_alive);
double interpolate(double t, double T, double p0_pos, double p1_pos, double p0_vel, double p1_vel);

public:
TrajectoryFollower(URCommander &commander, std::string &reverse_ip, int reverse_port, bool version_3);
TrajectoryFollower(URCommander& commander, std::string& reverse_ip, int reverse_port, bool version_3);

bool start();
bool execute(std::array<double, 6> &positions);
bool execute(std::vector<TrajectoryPoint> &trajectory, std::atomic<bool> &interrupt);
bool execute(std::array<double, 6>& positions);
bool execute(std::vector<TrajectoryPoint>& trajectory, std::atomic<bool>& interrupt);
void stop();

virtual ~TrajectoryFollower(){};
Expand Down
6 changes: 3 additions & 3 deletions include/ur_rtde_driver/ros/urscript_handler.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,12 +30,12 @@ class URScriptHandler : public Service
{
private:
ros::NodeHandle nh_;
URCommander &commander_;
URCommander& commander_;
ros::Subscriber urscript_sub_;
RobotState state_;

public:
URScriptHandler(URCommander &commander);
void urscriptInterface(const std_msgs::String::ConstPtr &msg);
URScriptHandler(URCommander& commander);
void urscriptInterface(const std_msgs::String::ConstPtr& msg);
void onRobotStateChange(RobotState state);
};
10 changes: 5 additions & 5 deletions include/ur_rtde_driver/tcp_socket.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,13 +39,13 @@ class TCPSocket
std::atomic<SocketState> state_;

protected:
virtual bool open(int socket_fd, struct sockaddr *address, size_t address_len)
virtual bool open(int socket_fd, struct sockaddr* address, size_t address_len)
{
return false;
}
virtual void setOptions(int socket_fd);

bool setup(std::string &host, int port);
bool setup(std::string& host, int port);

public:
TCPSocket();
Expand All @@ -64,9 +64,9 @@ class TCPSocket

std::string getIP();

bool read(char *character);
bool read(uint8_t *buf, size_t buf_len, size_t &read);
bool write(const uint8_t *buf, size_t buf_len, size_t &written);
bool read(char* character);
bool read(uint8_t* buf, size_t buf_len, size_t& read);
bool write(const uint8_t* buf, size_t buf_len, size_t& written);

void close();
};
28 changes: 14 additions & 14 deletions include/ur_rtde_driver/ur/commander.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,23 +25,23 @@
class URCommander
{
private:
URStream &stream_;
URStream& stream_;

protected:
bool write(const std::string &s);
void formatArray(std::ostringstream &out, std::array<double, 6> &values);
bool write(const std::string& s);
void formatArray(std::ostringstream& out, std::array<double, 6>& values);

public:
URCommander(URStream &stream) : stream_(stream)
URCommander(URStream& stream) : stream_(stream)
{
}

virtual bool speedj(std::array<double, 6> &speeds, double acceleration) = 0;
virtual bool speedj(std::array<double, 6>& speeds, double acceleration) = 0;
virtual bool setDigitalOut(uint8_t pin, bool value) = 0;
virtual bool setAnalogOut(uint8_t pin, double value) = 0;

// shared
bool uploadProg(const std::string &s);
bool uploadProg(const std::string& s);
bool stopj(double a = 10.0);
bool setToolVoltage(uint8_t voltage);
bool setFlag(uint8_t pin, bool value);
Expand All @@ -51,43 +51,43 @@ class URCommander
class URCommander_V1_X : public URCommander
{
public:
URCommander_V1_X(URStream &stream) : URCommander(stream)
URCommander_V1_X(URStream& stream) : URCommander(stream)
{
}

virtual bool speedj(std::array<double, 6> &speeds, double acceleration);
virtual bool speedj(std::array<double, 6>& speeds, double acceleration);
virtual bool setDigitalOut(uint8_t pin, bool value);
virtual bool setAnalogOut(uint8_t pin, double value);
};

class URCommander_V3_X : public URCommander
{
public:
URCommander_V3_X(URStream &stream) : URCommander(stream)
URCommander_V3_X(URStream& stream) : URCommander(stream)
{
}

virtual bool speedj(std::array<double, 6> &speeds, double acceleration) = 0;
virtual bool speedj(std::array<double, 6>& speeds, double acceleration) = 0;
virtual bool setDigitalOut(uint8_t pin, bool value);
virtual bool setAnalogOut(uint8_t pin, double value);
};

class URCommander_V3_1__2 : public URCommander_V3_X
{
public:
URCommander_V3_1__2(URStream &stream) : URCommander_V3_X(stream)
URCommander_V3_1__2(URStream& stream) : URCommander_V3_X(stream)
{
}

virtual bool speedj(std::array<double, 6> &speeds, double acceleration);
virtual bool speedj(std::array<double, 6>& speeds, double acceleration);
};

class URCommander_V3_3 : public URCommander_V3_X
{
public:
URCommander_V3_3(URStream &stream) : URCommander_V3_X(stream)
URCommander_V3_3(URStream& stream) : URCommander_V3_X(stream)
{
}

virtual bool speedj(std::array<double, 6> &speeds, double acceleration);
virtual bool speedj(std::array<double, 6>& speeds, double acceleration);
};
6 changes: 3 additions & 3 deletions include/ur_rtde_driver/ur/server.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ class URServer : private TCPSocket
TCPSocket client_;

protected:
virtual bool open(int socket_fd, struct sockaddr *address, size_t address_len);
virtual bool open(int socket_fd, struct sockaddr* address, size_t address_len);

public:
URServer(int port);
Expand All @@ -44,6 +44,6 @@ class URServer : private TCPSocket
bool bind();
bool accept();
void disconnectClient();
bool readLine(char *buffer, size_t buf_len);
bool write(const uint8_t *buf, size_t buf_len, size_t &written);
bool readLine(char* buffer, size_t buf_len);
bool write(const uint8_t* buf, size_t buf_len, size_t& written);
};
18 changes: 9 additions & 9 deletions src/ros/hardware_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,15 +20,15 @@
#include "ur_rtde_driver/log.h"

const std::string JointInterface::INTERFACE_NAME = "hardware_interface::JointStateInterface";
JointInterface::JointInterface(std::vector<std::string> &joint_names)
JointInterface::JointInterface(std::vector<std::string>& joint_names)
{
for (size_t i = 0; i < 6; i++)
{
registerHandle(hardware_interface::JointStateHandle(joint_names[i], &positions_[i], &velocities_[i], &efforts_[i]));
}
}

void JointInterface::update(RTShared &packet)
void JointInterface::update(RTShared& packet)
{
positions_ = packet.q_actual;
velocities_ = packet.qd_actual;
Expand All @@ -41,14 +41,14 @@ WrenchInterface::WrenchInterface(std::string tcp_link)
registerHandle(hardware_interface::ForceTorqueSensorHandle("wrench", tcp_link, tcp_.begin(), tcp_.begin() + 3));
}

void WrenchInterface::update(RTShared &packet)
void WrenchInterface::update(RTShared& packet)
{
tcp_ = packet.tcp_force;
}

const std::string VelocityInterface::INTERFACE_NAME = "hardware_interface::VelocityJointInterface";
VelocityInterface::VelocityInterface(URCommander &commander, hardware_interface::JointStateInterface &js_interface,
std::vector<std::string> &joint_names, double max_vel_change)
VelocityInterface::VelocityInterface(URCommander& commander, hardware_interface::JointStateInterface& js_interface,
std::vector<std::string>& joint_names, double max_vel_change)
: commander_(commander), max_vel_change_(max_vel_change), prev_velocity_cmd_({ 0, 0, 0, 0, 0, 0 })
{
for (size_t i = 0; i < 6; i++)
Expand All @@ -72,16 +72,16 @@ bool VelocityInterface::write()

void VelocityInterface::reset()
{
for (auto &val : prev_velocity_cmd_)
for (auto& val : prev_velocity_cmd_)
{
val = 0;
}
}

const std::string PositionInterface::INTERFACE_NAME = "hardware_interface::PositionJointInterface";
PositionInterface::PositionInterface(TrajectoryFollower &follower,
hardware_interface::JointStateInterface &js_interface,
std::vector<std::string> &joint_names)
PositionInterface::PositionInterface(TrajectoryFollower& follower,
hardware_interface::JointStateInterface& js_interface,
std::vector<std::string>& joint_names)
: follower_(follower)
{
for (size_t i = 0; i < 6; i++)
Expand Down
Loading

0 comments on commit 99533e4

Please sign in to comment.