Added a new class to test the vrep communication in robots commanded by joints velocities
This commit is contained in:
@@ -21,7 +21,9 @@ struct RobotCoppeliaROSConfiguration
|
||||
int thread_sampling_time_nsec;
|
||||
int port;
|
||||
std::string ip;
|
||||
|
||||
std::vector<std::string> jointnames;
|
||||
std::string robot_mode;
|
||||
bool mirror_mode;
|
||||
};
|
||||
|
||||
class RobotCoppeliaRosInterface
|
||||
@@ -31,13 +33,18 @@ private:
|
||||
bool _should_shutdown() const;
|
||||
sas::Clock clock_;
|
||||
RobotCoppeliaROSConfiguration configuration_;
|
||||
std::string robot_mode_ = std::string("VelocityControl"); // PositionControl
|
||||
bool mirror_mode_ = false;
|
||||
double gain_ = 0.5;
|
||||
|
||||
|
||||
protected:
|
||||
ros::NodeHandle nh_;
|
||||
VectorXd joint_positions_;
|
||||
VectorXd target_joint_positions_;
|
||||
VectorXd target_joint_velocities_;
|
||||
std::string topic_prefix_;
|
||||
ros::Publisher publisher_target_joint_positions_;
|
||||
//ros::Publisher publisher_target_joint_positions_;
|
||||
ros::Publisher publisher_joint_states_;
|
||||
//ros::Subscriber subscriber_joint_state_;
|
||||
ros::Subscriber subscriber_target_joint_positions_;
|
||||
@@ -47,6 +54,7 @@ protected:
|
||||
std::shared_ptr<DQ_VrepInterface> vi_;
|
||||
void _joint_states_callback(const sensor_msgs::JointState::ConstPtr& jointstate);
|
||||
void _callback_target_joint_positions(const std_msgs::Float64MultiArrayConstPtr &msg);
|
||||
void _callback_target_joint_velocities(const std_msgs::Float64MultiArrayConstPtr& msg);
|
||||
|
||||
void send_joint_states(const VectorXd &joint_positions, const VectorXd &joint_velocities, const VectorXd &joint_forces);
|
||||
|
||||
@@ -54,15 +62,15 @@ protected:
|
||||
public:
|
||||
RobotCoppeliaRosInterface(const ros::NodeHandle& nh,
|
||||
const std::string& topic_prefix,
|
||||
const std::vector<std::string>& jointnames,
|
||||
const RobotCoppeliaROSConfiguration& configuration,
|
||||
std::atomic_bool* kill_this_node);
|
||||
|
||||
RobotCoppeliaRosInterface()=delete;
|
||||
|
||||
~RobotCoppeliaRosInterface();
|
||||
VectorXd get_joint_positions() const;
|
||||
void set_joint_target_positions(const VectorXd& target_joint_positions);
|
||||
void set_joint_target_velocities(const VectorXd& target_joint_velocities);
|
||||
//VectorXd get_joint_positions() const;
|
||||
//void set_joint_target_positions(const VectorXd& target_joint_positions);
|
||||
|
||||
//void set_joint_target_positions_(const VectorXd& target_joint_positions);
|
||||
int control_loop();
|
||||
};
|
||||
|
||||
Reference in New Issue
Block a user