5 #ifndef ROS_REFLEXXES_ROSREFLEXXESINTERFACE_H 6 #define ROS_REFLEXXES_ROSREFLEXXESINTERFACE_H 21 virtual void starting(
const std::vector<double> &initial_command) = 0;
22 virtual std::vector<double>
update() = 0;
24 std::vector<double>
update(
const std::vector<double> &command) {
46 #endif //ROS_REFLEXXES_ROSREFLEXXESINTERFACE_H virtual void set_target_position(const std::vector< double > &t_pos)=0
virtual std::vector< double > get_current_velocity()=0
virtual std::vector< double > get_target_command()=0
virtual void set_target_command(const std::vector< double > &command)=0
virtual ~RosReflexxesInterface()
std::vector< double > update(const std::vector< double > &command)
virtual void starting(const std::vector< double > &initial_command)=0
ROSLIB_DECL std::string command(const std::string &cmd)
virtual std::vector< double > get_current_acceleration()=0
virtual void set_target_velocity(const std::vector< double > &t_vel)=0
virtual std::vector< double > update()=0
virtual bool init(ros::NodeHandle nh)=0
virtual std::vector< double > get_current_position()=0