1
0
mirror of https://gitlab.com/obbart/universal_robots_ros_driver.git synced 2026-04-10 01:50:46 +02:00

Updated clang-format and added clang-tidy instructions

This commit is contained in:
Felix Mauch
2019-04-01 11:18:59 +02:00
parent 5934612a03
commit 99533e42d8
16 changed files with 133 additions and 105 deletions

View File

@@ -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)
{
}
@@ -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(){};
};

View File

@@ -49,8 +49,8 @@ private:
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;
@@ -62,7 +62,7 @@ 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;
};
@@ -70,13 +70,13 @@ public:
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;
@@ -86,12 +86,12 @@ public:
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();

View File

@@ -34,7 +34,7 @@ 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_,
@@ -42,14 +42,14 @@ private:
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(){};

View File

@@ -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(){};

View File

@@ -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);
};

View File

@@ -39,13 +39,13 @@ private:
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();
@@ -64,9 +64,9 @@ public:
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();
};

View File

@@ -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);
@@ -51,11 +51,11 @@ public:
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);
};
@@ -63,11 +63,11 @@ public:
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);
};
@@ -75,19 +75,19 @@ public:
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);
};

View File

@@ -35,7 +35,7 @@ private:
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);
@@ -44,6 +44,6 @@ public:
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);
};