罗技f710遥控ur5

罗技F710遥控UR5

ur_mordern_driver中提供了对ur的速度控制。我写了一段简单的代码进行遥控,整体运行还行。

首先按照教程安装手柄的驱动


-  sudo apt-get install ros-kinetic-joy
-  rosdep install joy
-  rosmake joy
-  ls -l /dev/input/js0

安装好驱动之后测试按键

- roscore
- rosrun joy joy_node
- rostopic echo /joy

罗技f710遥控ur5_第1张图片

接下来是驱动代码


#include "ur_modern_driver/ur_driver.h"
#include 
#include 
#include "ur_driver.cpp"
#include "do_output.cpp"
#include "robot_state.cpp"
#include "ur_communication.cpp"
#include "ur_hardware_interface.cpp"
#include "ur_realtime_communication.cpp"
#include "robot_state_RT.cpp"
#include 
#include 


class urjoy
{

private :
  ros::NodeHandle nh;
  ros::Subscriber subjoy_;
  unsigned int reverse_port=50007;
  double servtime=0.016;
  unsigned int safe=12;
  double max=0.08;
  double maxload=1.0;
  double minload=0.;
  double serj_time=0.03;
  double sergain=300.;
  int i=10000;
  std::condition_variable cv1;
  std::condition_variable cv2;
  std::string ip="192.168.1.5";

  bool flag[6]={true,true,true,true,true,true};


public:
  void joyCallback(const sensor_msgs::Joy::ConstPtr &msg);
  urjoy(int argc,char **argv);
  UrDriver ur;
  double q[6]={0.,0.,0.,0.,0.,0.};
};


urjoy::urjoy(int argc,char **argv):  ur(cv1,cv2,ip,reverse_port,servtime,safe,max,minload,maxload,serj_time,sergain)
{

  ROS_INFO("dengdeng1");
  ur.start();
  ROS_INFO("dengdeng2");
  ur.uploadProg();
  ROS_INFO("dengdeng3");
  subjoy_=nh.subscribe("joy",100,&urjoy::joyCallback,this);
}

void urjoy::joyCallback(const sensor_msgs::Joy::ConstPtr&msg)
{

    std::ostringstream strs;
    strs << std::endl << "axes: [";
    for(size_t i=0; i < msg->axes.size(); i++)
        strs << msg->axes[i] << ",";
    strs << "]" << std::endl;
    strs << "button: [";
    for(size_t i=0; i < msg->buttons.size(); i++)
       { strs << msg->buttons[i] << ",";

       if(msg->buttons[i])
       {

         q[i]=0.2;
       if(msg->buttons[6])
         q[i]=-0.2;
       }

       else
         q[i]=0;

      }

    strs << "]" << std::endl;
    std::string str;
    str = strs.str();
    ROS_INFO("%2f %2f %2f %2f %2f %2f", q[0],q[1],q[2],q[3],q[4],q[5]);

}
int main(int argc, char **argv)
{

 ros::init(argc, argv, "urjoy");
 urjoy urjoy(argc,argv);
 ros::Rate loop_rate(125);
 while (ros::ok())
 {

  if(urjoy.q[0]+urjoy.q[1]+urjoy.q[2]+urjoy.q[3]+urjoy.q[4]+urjoy.q[5])
  {
    ROS_INFO("%2f %2f %2f %2f %2f %2f", urjoy.q[0],urjoy.q[1],urjoy.q[2],urjoy.q[3],urjoy.q[4],urjoy.q[5]);
  urjoy.ur.setSpeed(urjoy.q[0],urjoy.q[1],urjoy.q[2],urjoy.q[3],urjoy.q[4],urjoy.q[5],20.);
  }
  ros::spinOnce();
  loop_rate.sleep();
 }
 return 0;
}

罗技f710遥控ur5_第2张图片

本处直接控制ur5各关节的速度
后面将做tcp的遥控

你可能感兴趣的:(UR5)