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

Format sources with clang-format

This commit is contained in:
Miguel Prada
2018-11-20 09:47:17 +01:00
parent d7a59872b2
commit 9e276a3368
20 changed files with 177 additions and 163 deletions

View File

@@ -28,5 +28,5 @@ public:
virtual bool start() = 0;
virtual bool execute(std::vector<TrajectoryPoint> &trajectory, std::atomic<bool> &interrupt) = 0;
virtual void stop() = 0;
virtual ~ActionTrajectoryFollowerInterface() {};
virtual ~ActionTrajectoryFollowerInterface(){};
};

View File

@@ -9,11 +9,11 @@
#include <thread>
#include <vector>
#include "ur_modern_driver/log.h"
#include "ur_modern_driver/ros/action_trajectory_follower_interface.h"
#include "ur_modern_driver/ur/commander.h"
#include "ur_modern_driver/ur/server.h"
#include "ur_modern_driver/ros/action_trajectory_follower_interface.h"
class LowBandwidthTrajectoryFollower: public ActionTrajectoryFollowerInterface
class LowBandwidthTrajectoryFollower : public ActionTrajectoryFollowerInterface
{
private:
std::atomic<bool> running_;
@@ -21,14 +21,13 @@ private:
URCommander &commander_;
URServer server_;
double time_interval_, servoj_time_, servoj_time_waiting_, max_waiting_time_, \
servoj_gain_, servoj_lookahead_time_, max_joint_difference_;
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, double time_in_seconds);
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);
@@ -37,5 +36,5 @@ public:
bool execute(std::vector<TrajectoryPoint> &trajectory, std::atomic<bool> &interrupt);
void stop();
virtual ~LowBandwidthTrajectoryFollower() {};
virtual ~LowBandwidthTrajectoryFollower(){};
};

View File

@@ -35,8 +35,9 @@ private:
void publishRobotStatus(const RobotModeData_V3_0__1& data) const;
public:
MBPublisher() : io_pub_(nh_.advertise<ur_msgs::IOStates>("ur_driver/io_states", 1))
, status_pub_(nh_.advertise<industrial_msgs::RobotStatus>("ur_driver/robot_status", 1))
MBPublisher()
: io_pub_(nh_.advertise<ur_msgs::IOStates>("ur_driver/io_states", 1))
, status_pub_(nh_.advertise<industrial_msgs::RobotStatus>("ur_driver/robot_status", 1))
{
}

View File

@@ -9,9 +9,9 @@
#include <thread>
#include <vector>
#include "ur_modern_driver/log.h"
#include "ur_modern_driver/ros/action_trajectory_follower_interface.h"
#include "ur_modern_driver/ur/commander.h"
#include "ur_modern_driver/ur/server.h"
#include "ur_modern_driver/ros/action_trajectory_follower_interface.h"
class TrajectoryFollower : public ActionTrajectoryFollowerInterface
{
@@ -43,5 +43,5 @@ public:
bool execute(std::vector<TrajectoryPoint> &trajectory, std::atomic<bool> &interrupt);
void stop();
virtual ~TrajectoryFollower() {};
virtual ~TrajectoryFollower(){};
};

View File

@@ -8,10 +8,9 @@
#include "ur_modern_driver/ros/service_stopper.h"
#include "ur_modern_driver/ur/commander.h"
class URScriptHandler: public Service
class URScriptHandler : public Service
{
private:
ros::NodeHandle nh_;
URCommander &commander_;
ros::Subscriber urscript_sub_;
@@ -19,6 +18,6 @@ private:
public:
URScriptHandler(URCommander &commander);
void urscriptInterface(const std_msgs::String::ConstPtr& msg);
void urscriptInterface(const std_msgs::String::ConstPtr &msg);
void onRobotStateChange(RobotState state);
};