当前位置:   article > 正文

ros之真实驱动diy6自由度机械臂(moveit中controller源码)_moveit智能机械臂六自由度手臂

moveit智能机械臂六自由度手臂



书接上回,

moveit 控制真实机器手臂时需要自己编写 控制器,控制器要有一个action server来接收 moveit的路径消息,然后控制器把消息下发到硬件上。

moveit 需要控制器获取并发布机机器手臂的状态。

此处创建两个节点,来实现这些功能。

第一个节点jointcontroller

1、负责 action server 功能,

2、路径消息转换成电机Id +角度r的一个新消息(joint_msg),并发布/arm_motors的话题.

3、由于是舵机,并不能获取其位姿,获取部分省略。

4、发布舵机的当前位姿,即 从接收的路径消息来转换成joint_state消息,并发布/move_group/fake_controller_joint_states的话题。


第二个节点jointserial

接收话题/arm_motors,解析joint_msg 通过自定义协议串口下发。






自定义消息

joint_msg

  1. int32 id
  2. float64 r




jointcontroller.cpp

  1. #include <ros/ros.h>
  2. #include <actionlib/server/simple_action_server.h>
  3. #include <control_msgs/FollowJointTrajectoryAction.h>
  4. #include <trajectory_msgs/JointTrajectory.h>
  5. #include <std_msgs/Float64.h>
  6. #include <iostream>
  7. #include <vector>
  8. #include <string>
  9. #include <sensor_msgs/JointState.h>
  10. #include <map>
  11. #include "zzz_arm_control_driver/joint_msg.h"
  12. using namespace std ;
  13. typedef actionlib::SimpleActionServer<control_msgs::FollowJointTrajectoryAction> Server;
  14. class RobotTrajectoryFollower
  15. {
  16. protected:
  17. ros::NodeHandle nh_;
  18. // NodeHandle instance must be created before this line. Otherwise strange error may occur.
  19. //actionlib::SimpleActionServer<control_msgs::FollowJointTrajectoryAction> as_;
  20. std::string action_name_;
  21. ros::Publisher joint_pub ;
  22. ros::Publisher joint_motor_pub ;
  23. sensor_msgs::JointState joint_state;
  24. zzz_arm_control_driver::joint_msg joint_motor_msg;
  25. control_msgs::FollowJointTrajectoryResult result_;
  26. control_msgs::FollowJointTrajectoryActionGoal agoal_;
  27. control_msgs::FollowJointTrajectoryActionFeedback afeedback_;
  28. control_msgs::FollowJointTrajectoryFeedback feedback_;
  29. public:
  30. map< string, int > MotoName_Id;
  31. RobotTrajectoryFollower(std::string name) :
  32. nh_("~"),
  33. as_(nh_, name,boost::bind(&RobotTrajectoryFollower::goalCB, this, _1), false),
  34. action_name_(name)
  35. {
  36. /*<!--
  37. shoulder_wan_joint:1
  38. upper_arm_joint:2
  39. middle_arm_joint:3
  40. fore_arm_joint:4
  41. tool_joint:5 -->*/
  42. nh_.param("shoulder_wan_joint", MotoName_Id["shoulder_wan_joint"], 0);
  43. nh_.param("upper_arm_joint", MotoName_Id["upper_arm_joint"], 0);
  44. nh_.param("middle_arm_joint", MotoName_Id["middle_arm_joint"], 0);
  45. nh_.param("fore_arm_joint", MotoName_Id["fore_arm_joint"], 0);
  46. nh_.param("tool_joint", MotoName_Id["tool_joint"], 10);
  47. joint_pub = nh_.advertise<sensor_msgs::JointState>("/move_group/fake_controller_joint_states", 1);
  48. joint_motor_pub = nh_.advertise<zzz_arm_control_driver::joint_msg>("/arm_motors", 1000);
  49. //Register callback functions:
  50. //as_.registerGoalCallback(boost::bind(&RobotTrajectoryFollower::goalCB, this,_1));
  51. as_.registerPreemptCallback(boost::bind(&RobotTrajectoryFollower::preemptCB, this));
  52. as_.start();
  53. }
  54. ~RobotTrajectoryFollower(void)//Destructor
  55. {
  56. }
  57. //
  58. void setJointStateName(std::vector<std::string> joint_names){
  59. joint_state.name.resize(joint_names.size());
  60. joint_state.name.assign(joint_names.begin(), joint_names.end());
  61. //joint_state.name[0] ="arm_1_to_arm_base";
  62. //std::vector<std::string>::iterator it;
  63. //for ( it = joint_state.name.begin(); it != joint_state.name.end(); it++){
  64. // cout <<(*it) <<endl;
  65. //}
  66. //cout <<endl ;
  67. }
  68. void setJointStatePosition(std::vector<double> joint_posi){
  69. joint_state.position.resize(joint_posi.size());
  70. joint_state.position.assign(joint_posi.begin(), joint_posi.end());
  71. //joint_state.position[0] = base_arm;
  72. //std::vector<double>::iterator it;
  73. //for ( it = joint_state.position.begin(); it != joint_state.position.end(); it++){
  74. // cout <<(*it) <<endl;
  75. //}
  76. //cout <<endl ;
  77. }
  78. void publishJointState(){
  79. joint_state.header.stamp = ros::Time::now();
  80. joint_pub.publish(joint_state);
  81. }
  82. void publishMotorState(int ids[],std::vector<double> joint_posi){
  83. std::vector<double>::iterator it;
  84. int i=0;
  85. for ( it = joint_posi.begin(); it != joint_posi.end(); it++,i++){
  86. joint_motor_msg.id=ids[i];
  87. joint_motor_msg.r=(*it) ;
  88. joint_motor_pub.publish(joint_motor_msg);
  89. cout <<joint_motor_msg <<endl;
  90. }
  91. }
  92. void goalCB(const control_msgs::FollowJointTrajectoryGoalConstPtr msg)
  93. {
  94. //cout<<((*msg))<<endl;
  95. std::vector<std::string> joint_names=(*msg).trajectory.joint_names;
  96. //
  97. setJointStateName( joint_names);
  98. std::vector<std::string>::iterator it;
  99. int ids [joint_names.size()];
  100. int i=0;
  101. for ( it = joint_names.begin(); it != joint_names.end(); it++,i++){
  102. ids[i]=MotoName_Id[(*it)];
  103. cout <<MotoName_Id[(*it)] <<endl;
  104. }
  105. //goal=(*msg);goal.trajectory.points;//c++ how to use this style??
  106. std::vector<trajectory_msgs::JointTrajectoryPoint> points = (*msg).trajectory.points;
  107. std::vector<trajectory_msgs::JointTrajectoryPoint>::iterator pointsit;
  108. ros::Rate rate(10);//10hz
  109. size_t t=points.size();
  110. ROS_INFO("%s: goalCB ", action_name_.c_str());
  111. for ( pointsit = points.begin(); pointsit != points.end(); pointsit++){
  112. //cout<<(*pointsit)<<endl;
  113. //cout <<endl ;
  114. //here send datamsg to hardware node,command motors run.
  115. //
  116. publishMotorState(ids,(*pointsit).positions);
  117. //wait
  118. rate.sleep();
  119. //then update joinstates an publish
  120. setJointStatePosition((*pointsit).positions);
  121. publishJointState();
  122. //feedback_.
  123. //as_.publishFeedback(feedback_);
  124. ROS_INFO("left position :%d", (int)t);
  125. t--;
  126. }
  127. // accept the new goal
  128. //as_.acceptNewGoal();
  129. if(as_.isActive())as_.setSucceeded();
  130. }
  131. void preemptCB()
  132. {
  133. ROS_INFO("%s: Preempted", action_name_.c_str());
  134. // set the action state to preempted
  135. if(as_.isActive()){
  136. as_.setPreempted();
  137. }
  138. }
  139. Server as_;
  140. };
  141. int main(int argc, char** argv)
  142. {
  143. ros::init(argc, argv, "jointcontroller");
  144. RobotTrajectoryFollower RobotTrajectoryFollower("/zzz_arm_controller/follow_joint_trajectory");
  145. ;
  146. ROS_INFO("-------------zzz joint controller is running .");
  147. ros::spin();
  148. return 0;
  149. }


jointserial.cpp

  1. #include <ros/ros.h>
  2. #include <serial/serial.h>
  3. //ROS已经内置了的串口包
  4. #include <std_msgs/String.h>
  5. #include <std_msgs/Empty.h>
  6. #include "zzz_arm_control_driver/joint_msg.h"
  7. #include <boost/asio.hpp> //包含boost库函数
  8. using namespace boost::asio; //定义一个命名空间,用于后面的读写操作
  9. using namespace std;
  10. serial::Serial ser; //声明串口对象
  11. //io_service Object
  12. io_service m_ios;
  13. //Serial port Object
  14. serial_port *pSerialPort;
  15. //For save com name
  16. //any_type m_port;
  17. //Serial_port function exception
  18. boost::system::error_code ec;
  19. std::string serial_port_name;
  20. int serial_baudrate = 115200;
  21. unsigned char AA=1;
  22. unsigned char aa;
  23. //回调函数
  24. void write_callback(const zzz_arm_control_driver::joint_msg::ConstPtr& msg)
  25. {
  26. ROS_INFO_STREAM("Writing to serial port" <<msg->id<<msg->r);
  27. unsigned char mid=(char) msg->id;
  28. double r=msg->r;
  29. if(mid==1){
  30. r+=3.1415926536/4.0;//motor1 limit:-45~45
  31. }
  32. r=r<0.0?0.0:r;
  33. r=r>3.1415926/2.0?3.1415926/2.0:r;
  34. double per=r/(3.1415926/2.0);
  35. per=(mid==1||mid==5)?per:(1-per);
  36. unsigned short mr=(unsigned short )((per)*1024.0);
  37. ROS_INFO("id:%d per:%d",mid,mr);
  38. unsigned char* mrp= (unsigned char*)&mr;
  39. unsigned char b1,b2,b3;
  40. //11aa aaAA
  41. b1=0xc0|(mid<<2);
  42. b1|=0x03&(AA>>2);
  43. //10AA xxxx
  44. b2=0x80|(AA<<4);
  45. b2|=(0x0c&((*(mrp+1))<<2))|(0x03&((*(mrp))>>6));
  46. //01xx xxxx
  47. b3=0x40|(0x3f&(*(mrp)));
  48. char cdata[3];
  49. cdata[0]=b1;
  50. cdata[1]=b2;
  51. cdata[2]=b3;
  52. string data="";
  53. data+=b1;
  54. data+=b2;
  55. data+=b3;
  56. //ser.write(data);//发送串口数据
  57. try
  58. {
  59. size_t len = write( *pSerialPort, buffer( cdata,3 ), ec );
  60. }catch (boost::system::system_error e){
  61. ROS_ERROR_STREAM("serail write err ");
  62. }
  63. }
  64. int main (int argc, char** argv)
  65. {
  66. //初始化节点
  67. ros::init(argc, argv, "jointserial");
  68. //声明节点句柄
  69. ros::NodeHandle nh;
  70. //订阅主题,并配置回调函数
  71. ros::Subscriber write_sub = nh.subscribe("/arm_motors", 1000, write_callback);
  72. //发布主题
  73. //ros::Publisher read_pub = nh.advertise<std_msgs::String>("read", 1000);
  74. ros::NodeHandle nh_private("~");
  75. nh_private.param<std::string>("serial_port", serial_port_name, "/dev/ttyUSB0");
  76. nh_private.param<int>("serial_baudrate", serial_baudrate, 115200);
  77. /*try
  78. {
  79. //设置串口属性,并打开串口
  80. ROS_INFO("%s",serial_port_name.c_str());
  81. ser.setPort(serial_port_name);
  82. ser.setBaudrate(serial_baudrate);
  83. serial::Timeout to = serial::Timeout::simpleTimeout(10000);
  84. ser.setTimeout(to);
  85. ser.open();
  86. }
  87. catch (serial::IOException& e)
  88. {
  89. ROS_ERROR_STREAM("Unable to open port ");
  90. return -1;
  91. }
  92. //检测串口是否已经打开,并给出提示信息
  93. if(ser.isOpen())
  94. {
  95. ROS_INFO_STREAM("Serial Port initialized");
  96. }
  97. else
  98. {
  99. return -1;
  100. }//*/
  101. pSerialPort = new serial_port( m_ios );
  102. if ( pSerialPort ){
  103. //init_port( port_name, 8 );
  104. //Open Serial port object
  105. pSerialPort->open( serial_port_name, ec );
  106. //Set port argument
  107. pSerialPort->set_option( serial_port::baud_rate( serial_baudrate ), ec );
  108. pSerialPort->set_option( serial_port::flow_control( serial_port::flow_control::none ), ec );
  109. pSerialPort->set_option( serial_port::parity( serial_port::parity::none ), ec );
  110. pSerialPort->set_option( serial_port::stop_bits( serial_port::stop_bits::one ), ec);
  111. pSerialPort->set_option( serial_port::character_size( 8 ), ec);
  112. m_ios.run();
  113. }
  114. short int a = 0x1234;
  115. char *p = (char *)&a;
  116. ROS_INFO("p=%#hhx\n", *p);
  117. if (*p == 0x34) {
  118. ROS_INFO("little endian\n");
  119. } else if (*p == 0x12) {
  120. ROS_INFO("big endia\n");
  121. } else {
  122. ROS_INFO("unknown endia\n");
  123. }
  124. ROS_INFO("-------------zzz joint serail is running .");
  125. ros::spin();
  126. return 0;
  127. /*
  128. //指定循环的频率
  129. ros::Rate loop_rate(50);
  130. while(ros::ok())
  131. {
  132. if(ser.available()){
  133. ROS_INFO_STREAM("Reading from serial port\n");
  134. std_msgs::String result;
  135. result.data = ser.read(ser.available());
  136. ROS_INFO_STREAM("Read: " << result.data);
  137. read_pub.publish(result);
  138. }
  139. //处理ROS的信息,比如订阅消息,并调用回调函数
  140. ros::spinOnce();
  141. loop_rate.sleep();
  142. }*/
  143. }






声明:本文内容由网友自发贡献,不代表【wpsshop博客】立场,版权归原作者所有,本站不承担相应法律责任。如您发现有侵权的内容,请联系我们。转载请注明出处:https://www.wpsshop.cn/w/凡人多烦事01/article/detail/623736
推荐阅读
  

闽ICP备14008679号