18 #ifndef __GENERIC_ARM_CTRL_V4_H_ 19 #define __GENERIC_ARM_CTRL_V4_H_ 28 #include <trajectory_msgs/JointTrajectory.h> 37 genericArmCtrl(
int DOF,
double PTPvel = 0.7,
double PTPacc = 0.2,
double maxError = 0.7);
49 bool step(std::vector<double> current_pos, std::vector<double> & desired_vel);
51 bool moveThetas(std::vector<double> conf_goal, std::vector<double> conf_current);
52 bool moveTrajectory(trajectory_msgs::JointTrajectory pfad, std::vector<double> conf_current);
void SetPTPvel(double vel)
std::vector< double > last_q
bool step(std::vector< double > current_pos, std::vector< double > &desired_vel)
bool moveThetas(std::vector< double > conf_goal, std::vector< double > conf_current)
Will move the component to a goal configuration in Joint Space.
std::vector< double > m_vel_js
std::vector< double > m_acc_js
bool moveTrajectory(trajectory_msgs::JointTrajectory pfad, std::vector< double > conf_current)
genericArmCtrl(int DOF, double PTPvel=0.7, double PTPacc=0.2, double maxError=0.7)
std::vector< double > GetPTPacc() const
std::vector< double > last_q2
std::vector< double > GetPTPvel() const
void SetPTPacc(double acc)
std::vector< double > last_q3
std::vector< double > last_q1