mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-10 10:00:48 +02:00
Refactored intialisation of ROSController/ActionServer
This commit is contained in:
@@ -39,7 +39,7 @@ private:
|
||||
std::condition_variable tj_cv_;
|
||||
std::thread tj_thread_;
|
||||
|
||||
TrajectoryFollowerInterface& follower_;
|
||||
ActionTrajectoryFollowerInterface& follower_;
|
||||
|
||||
RobotState state_;
|
||||
std::array<double, 6> q_actual_, qd_actual_;
|
||||
@@ -61,7 +61,7 @@ private:
|
||||
bool updateState(RTShared& data);
|
||||
|
||||
public:
|
||||
ActionServer(TrajectoryFollowerInterface& follower, std::vector<std::string>& joint_names, double max_velocity);
|
||||
ActionServer(ActionTrajectoryFollowerInterface& follower, std::vector<std::string>& joint_names, double max_velocity);
|
||||
|
||||
void start();
|
||||
virtual void onRobotStateChange(RobotState state);
|
||||
|
||||
@@ -22,11 +22,11 @@ struct TrajectoryPoint
|
||||
}
|
||||
};
|
||||
|
||||
class TrajectoryFollowerInterface
|
||||
class ActionTrajectoryFollowerInterface
|
||||
{
|
||||
public:
|
||||
virtual bool start() = 0;
|
||||
virtual bool execute(std::vector<TrajectoryPoint> &trajectory, std::atomic<bool> &interrupt) = 0;
|
||||
virtual void stop() = 0;
|
||||
virtual ~TrajectoryFollowerInterface() {};
|
||||
virtual ~ActionTrajectoryFollowerInterface() {};
|
||||
};
|
||||
@@ -11,9 +11,9 @@
|
||||
#include "ur_modern_driver/log.h"
|
||||
#include "ur_modern_driver/ur/commander.h"
|
||||
#include "ur_modern_driver/ur/server.h"
|
||||
#include "ur_modern_driver/ros/trajectory_follower_interface.h"
|
||||
#include "ur_modern_driver/ros/action_trajectory_follower_interface.h"
|
||||
|
||||
class LowBandwidthTrajectoryFollower: public TrajectoryFollowerInterface
|
||||
class LowBandwidthTrajectoryFollower: public ActionTrajectoryFollowerInterface
|
||||
{
|
||||
private:
|
||||
std::atomic<bool> running_;
|
||||
|
||||
@@ -11,9 +11,9 @@
|
||||
#include "ur_modern_driver/log.h"
|
||||
#include "ur_modern_driver/ur/commander.h"
|
||||
#include "ur_modern_driver/ur/server.h"
|
||||
#include "ur_modern_driver/ros/trajectory_follower_interface.h"
|
||||
#include "ur_modern_driver/ros/action_trajectory_follower_interface.h"
|
||||
|
||||
class TrajectoryFollower : public TrajectoryFollowerInterface
|
||||
class TrajectoryFollower : public ActionTrajectoryFollowerInterface
|
||||
{
|
||||
private:
|
||||
std::atomic<bool> running_;
|
||||
|
||||
Reference in New Issue
Block a user