mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-10 01:50:46 +02:00
Added trajectory and actionlib interface
This commit is contained in:
@@ -15,20 +15,35 @@
|
||||
#include <mutex>
|
||||
#include <condition_variable>
|
||||
#include "ur_realtime_communication.h"
|
||||
#include <vector>
|
||||
#include <math.h>
|
||||
|
||||
class UrDriver {
|
||||
private:
|
||||
double maximum_time_step_;
|
||||
std::vector<std::string> joint_names_;
|
||||
public:
|
||||
UrRealtimeCommunication* rt_interface_;
|
||||
|
||||
UrDriver(std::condition_variable& msg_cond, std::string host,
|
||||
std::vector<std::string> joint_names,
|
||||
unsigned int safety_count_max = 12);
|
||||
void start();
|
||||
void halt();
|
||||
|
||||
void setSpeed(double q0, double q1, double q2, double q3, double q4,
|
||||
double q5, double acc = 100.);
|
||||
void addTraj(std::vector<double> inp_timestamps,
|
||||
std::vector<std::vector<double> > positions,
|
||||
std::vector<std::vector<double> > velocities);
|
||||
void stopTraj();
|
||||
|
||||
std::vector<double> interp_cubic(double t, double T,
|
||||
std::vector<double> p0_pos, std::vector<double> p1_pos,
|
||||
std::vector<double> p0_vel, std::vector<double> p1_vel);
|
||||
|
||||
std::vector<std::string> getJointNames();
|
||||
void setJointNames(std::vector<std::string> jn);
|
||||
};
|
||||
|
||||
#endif /* UR_DRIVER_H_ */
|
||||
|
||||
Reference in New Issue
Block a user