当前位置:   article > 正文

使用ros_control ros_controllers 的牛刀真实驱动舵机手臂的源码_controller is taking too long to execute trajector

controller is taking too long to execute trajectory (the expected upper boun

现场


rqt_graph

在一个陌生的框架下写代码,免不了有很多疑问与槽点。

不了解框架结构,千头万续,无从下手,说不清,理还乱。
资料少没有文档,要读懂程序猿的心,就只得静下心来穿针引线般的读代码了。
让我们从这里开始吧————这到底是个什么鬼?慢慢来,哈哈

原标题
ros_control是个什么东西?
http://www.360doc.com/content/16/0509/17/33166754_557610167.shtml


ROS control-----hardware_interface简介
http://blog.csdn.net/x_r_su/article/details/53284477

RosControl学习
http://blog.csdn.net/sunanger/article/details/53033630

官方
ros_control
http://wiki.ros.org/ros_control

还是这张图看上100遍





读了这几篇,从大框框上认识一下,需要注意的点做个总结。(部分描述copy原文)
ros_control定义了机器人硬件接口和机器人控制器的抽象接口,控制器管理类controller_manager类,
其网址为: https://github.com/ros-controls/ros_control
控制器(ros_controllers)的实现类是在ros_controllers包内实现的,
其网址为: https://github.com/shadow-robot/ros_controllers

ros_control  ros_controllers密切联系点
ros_controllers包中每个XXXController继承了ros_control包内的Controller

深入源码看看

ros_control包下controller_interface空间中Controller类
class Controller: public ControllerBase


抽象类ControllerBase中虚函数starting,stoping,update
ros_controllers包下joint_trajectory_controller空间中JointTrajectoryController类
class JointTrajectoryController : public controller_interface::Controller<HardwareInterface>


实现了
  1. bool init(HardwareInterface* hw, ros::NodeHandle& root_nh, ros::NodeHandle& controller_nh);
  2. void starting(const ros::Time& time);
  3. void stopping(const ros::Time& /*time*/);
  4. void update(const ros::Time& time, const ros::Duration& period);


注:JointTrajectoryController本质上是actionserver,驱动机械臂时,它和moveit的client进行交互。




gazebo仿真时
自定义插件类必须继承自gazebo_ros_control::RobotHWSim实现了模拟ros_control包中的hardware_interface::RobotHW
插件类必须实现initSim readSim writeSim

驱动真实硬件时用到ros_control类库 也要实现gezabo插件类类似的功能
写一个类继承 hardware_interface::RobotHW,用来实现各种硬件接口的注册
RobotHW 类派生自InterfaceManger
InterfaceManger类为接口管理类,提供有registerInterface函数,用于注册机器人硬件的接口类(**Interface),并可以用T* Get()函数获取接口类的对象
  1. hardware_interface::JointStateInterface js_interface_;
  2. hardware_interface::PositionJointInterface pj_interface_;
  3. //....
  4. // Register interfaces
  5. registerInterface(&js_interface_);
  6. registerInterface(&pj_interface_);




JointStateInterface继承了HardwareResourceManager
class JointStateInterface : public HardwareResourceManager<JointStateHandle> {}



HardwareResourceManger类继承了HardwareInterface和ResourceManger<ResourceHandle>,
class HardwareResourceManager : public HardwareInterface, public ResourceManager<ResourceHandle>



HardwareInterface
提供claim()和clearClaim()函数用于声索资源和清除声索资源;
ResourceManger<ResourceHandle>
提供registerHandle(ResourceHandle handle)向接口类注册资源handle
提供gethandle(name)获取handle对象。

层层继承下来所以JointStateInterface具有registerHandle(ResourceHandle handle)gethandle(name)功能。



  1. unsigned int n_dof_;
  2. std::vector<std::string> joint_names_;
  3. std::vector<double> joint_position_;
  4. std::vector<double> joint_velocity_;
  5. std::vector<double> joint_effort_;
  6. std::vector<double> joint_position_command_;
  7. joint_names_.push_back("_joint0");
  8. joint_names_.push_back("_joint1");
  9. joint_names_.push_back("_joint2");
  10. n_dof_ = joint_names_.size();
  11. joint_position_.resize(n_dof_);
  12. joint_velocity_.resize(n_dof_);
  13. joint_effort_.resize(n_dof_);
  14. joint_position_command_.resize(n_dof_);
  15. for (std::size_t i = 0; i < n_dof_; ++i)
  16. {
  17. // Create joint state interface for all joints
  18. //JointstateHandle为关节状态的资源类,其内部存储有:pos,vel,effort的获取接口。
  19. js_interface.registerHandle(hardware_interface::JointStateHandle(
  20. joint_names_[i], &joint_position_[i], &joint_velocity_[i], &joint_effort_[i]));
  21. // Create position joint interface
  22. /*
  23. 类似于JointStateInterface和JointstateHandle的一组接口资源类,还有JointHandle和JointCommandInterface,其中JointHandle不但包含了Jointstatehandle的所有内容,还包括了setcommand和getcommand两个命令接口,从这个JointCommandInterface类还派生出了PositionJointInterface,VelocityJointInterface,EffortJointInterface等类,其本质是一回事,就是实现一个控制量的读取和写入接口,同时获取joint的状态。
  24. */
  25. pj_interface.registerHandle(hardware_interface::JointHandle(
  26. js_interface.getHandle(joint_names_[i]),&joint_position_command_[i]));
  27. }



官方简例代码
https://github.com/ros-controls/ros_controllers/blob/indigo-devel/diff_drive_controller/test/diffbot.h

https://github.com/ros-controls/ros_controllers/blob/indigo-devel/diff_drive_controller/test/diffbot.cpp


不难看出要让controller manager和controller协作,就须遵循下面的套路。

  1. main()
  2. {
  3. MyRobot robot;//这个class MyRobot 继承 hardware_interface::RobotHW实现read() write()
  4. controller_manager::ControllerManager cm(&robot);
  5. while (true)
  6. {
  7. robot.read(); //to access hardware driver, generally need do some wrap and customization in MyRobot class
  8. cm.update(robot.get_time(), robot.get_period());
  9. robot.write(); //to access hardware driver, generally need do some wrap and customization in MyRobot class
  10. sleep();
  11. }
  12. }



实现read write 的实现并不一定在robot类里,看具体需求,只要在合适的位置循环调用就好了,如下文官方给的baxter实例的read和write,并且是使用定时器触发代替循环的,详细请自行慢慢观摩。
实现硬件协议可以是串口 can总线或其他,我这里是用串口,关于驱动源码请看下面裸跑实例内的链接。
驱动手臂只要能给硬件下发消息,能读回关节状态就好。
其实抛弃ros_contrl裸跑其实更直观/简单/更好理解一些。
裸跑实例源码。
http://blog.csdn.net/qq_38288618/article/details/78078514
两点
moveit 控制真实机器手臂时需要controller接收 moveit的路径消息,然后把消息write到硬件上。
moveit 需要read机器手臂的状态join_states


使用ros_control的好处
只需把yaml写好 JointTrajectoryController和moveit自动取得联系。
不用自己处理actionserver
框架功能强大

让我们开始创作代码吧
......怎么,线头太多不知从何处开始,好吧,似乎还是写不出来一个实例。
那让我们找个源码做手术吧,改改改。
官方提供了Baxter的代码实例
Rethink Baxter hardware as used at the University of Colorado Boulder: Baxter on Github
https://github.com/davetcoleman/baxter_cpp/blob/hydro-devel/baxter_control/src/baxter_hardware_interface.cpp


https://github.com/davetcoleman/baxter_cpp/整个down下来
就拿它开刀!目的就是嫁接在自己的舵机手臂上能使。
仿真的部分略过不做处理,只拿自己要的。不需要的部分注释加删除,按需要添加改名。

主要修改双手臂为单手臂,关节名称,尝试调用PID的yaml信息等等,实现真实手臂运动规划的走位。
(抓手的controller没有做,由于抓手是一个电机控制两个抓手开合,应该需要写一个简单映射或者动力学的公式才行,这里翻篇)。


冗长代码开始之前先看看Baxter


代码开启

arm_interface.h

  1. #ifndef BAXTER_CONTROL__ARM_INTERFACE_
  2. #define BAXTER_CONTROL__ARM_INTERFACE_
  3. // Boost
  4. #include <boost/shared_ptr.hpp>
  5. // ROS
  6. #include <ros/ros.h>
  7. #include <sensor_msgs/JointState.h>
  8. // ros_control
  9. #include <hardware_interface/joint_command_interface.h>
  10. #include <hardware_interface/joint_state_interface.h>
  11. //#include <hardware_interface/joint_mode_interface.h>
  12. // Baxter
  13. //#include <baxter_core_msgs/JointCommand.h>
  14. //#include <baxter_core_msgs/JointCommand.h>
  15. namespace zzz_arm_2_control
  16. {
  17. enum BaxterControlMode { POSITION, VELOCITY, TORQUE };
  18. class ArmInterface
  19. {
  20. protected:
  21. // Node Handles
  22. ros::NodeHandle nh_; // no namespace
  23. // Number of joints we are using
  24. unsigned int n_dof_;
  25. std::vector<std::string> joint_names_;
  26. std::vector<double> joint_position_;
  27. std::vector<double> joint_velocity_;
  28. std::vector<double> joint_effort_;
  29. std::vector<double> joint_position_command_;
  30. std::vector<double> joint_effort_command_;
  31. std::vector<double> joint_velocity_command_;
  32. // Track current hardware interface mode we are in
  33. int* joint_mode_;
  34. // Speed of hardware loop
  35. double loop_hz_;
  36. // Name of this arm
  37. std::string arm_name_;
  38. public:
  39. /**
  40. * \brief Constructor/Descructor
  41. */
  42. ArmInterface(const std::string &arm_name, double loop_hz)
  43. : arm_name_(arm_name),
  44. loop_hz_(loop_hz)
  45. {};
  46. ~ArmInterface()
  47. {};
  48. /**
  49. * \brief Initialice hardware interface
  50. * \return false if an error occurred during initialization
  51. */
  52. virtual bool init(
  53. hardware_interface::JointStateInterface& js_interface,
  54. hardware_interface::EffortJointInterface& ej_interface,
  55. hardware_interface::VelocityJointInterface& vj_interface,
  56. hardware_interface::PositionJointInterface& pj_interface,
  57. int* joint_mode,
  58. sensor_msgs::JointStateConstPtr state_msg
  59. )
  60. { return true; };
  61. /**
  62. * \brief Copy the joint state message into our hardware interface datastructures
  63. */
  64. virtual void read( sensor_msgs::JointStateConstPtr &state_msg )
  65. {};
  66. /**
  67. * \brief Publish our hardware interface datastructures commands to Baxter hardware
  68. */
  69. virtual void write(ros::Duration elapsed_time)
  70. {};
  71. /**
  72. * \brief This is called when Baxter is disabled, so that we can update the desired positions
  73. */
  74. virtual void robotDisabledCallback()
  75. {};
  76. };
  77. typedef boost::shared_ptr<zzz_arm_2_control::ArmInterface> ArmInterfacePtr;
  78. typedef boost::shared_ptr<const zzz_arm_2_control::ArmInterface> ArmInterfaceConstPtr;
  79. } // namespace
  80. #endif

arm_hardware_interface.h


  1. #ifndef BAXTER_CONTROL__ARM_HARDWARE_INTERFACE_
  2. #define BAXTER_CONTROL__ARM_HARDWARE_INTERFACE_
  3. // ROS
  4. #include <trajectory_msgs/JointTrajectory.h>
  5. // Baxter
  6. //#include <baxter_core_msgs/JointCommand.h>
  7. //#include <baxter_core_msgs/DigitalIOState.h>
  8. // Parent class
  9. #include <zzz_arm_2_hardware/arm_interface.h>
  10. #include <vector>
  11. #include <string>
  12. #include <control_toolbox/pid.h>
  13. #include <joint_limits_interface/joint_limits_interface.h>
  14. namespace zzz_arm_2_control
  15. {
  16. static const double STATE_EXPIRED_TIMEOUT = 2.0;
  17. class ArmHardwareInterface : public ArmInterface
  18. {
  19. private:
  20. // Publishers
  21. ros::Publisher pub_joint_command_;
  22. ros::Publisher pub_trajectory_command_;
  23. ros::Publisher zzz_fake_joint_pub_ ;
  24. ros::Publisher joint_motor_pub_ ;
  25. // Subscriber
  26. ros::Subscriber cuff_squeezed_sub_; // this is used to update the controllers when manual mode is started
  27. // Messages to send
  28. //baxter_core_msgs::JointCommand output_msg_;
  29. trajectory_msgs::JointTrajectory trajectory_command_msg_;
  30. // Track button status
  31. bool cuff_squeezed_previous;
  32. // Convert a joint states message to our ids
  33. std::vector<int> joint_id_to_joint_states_id_;
  34. //zzzadd
  35. // Joint limits interface
  36. joint_limits_interface::PositionJointSoftLimitsInterface jnt_limits_interface_;
  37. // PID controllers
  38. std::vector<control_toolbox::Pid> pids_;
  39. template <class T>
  40. std::string containerToString(const T& cont, const std::string& prefix)
  41. {
  42. std::stringstream ss;
  43. ss << prefix;
  44. std::copy(cont.begin(), --cont.end(), std::ostream_iterator<typename T::value_type>(ss, prefix.c_str()));
  45. ss << *(--cont.end());
  46. return ss.str();
  47. }
  48. public:
  49. /**
  50. * \brief Constructor/Descructor
  51. */
  52. ArmHardwareInterface(const std::string &arm_name, double loop_hz);
  53. ~ArmHardwareInterface();
  54. /**
  55. * \brief Initialice hardware interface
  56. * \return false if an error occurred during initialization
  57. */
  58. bool init(
  59. hardware_interface::JointStateInterface& js_interface,
  60. hardware_interface::EffortJointInterface& ej_interface,
  61. hardware_interface::VelocityJointInterface& vj_interface,
  62. hardware_interface::PositionJointInterface& pj_interface,
  63. int* joint_mode,
  64. sensor_msgs::JointStateConstPtr state_msg
  65. );
  66. /**
  67. * \brief Buffers joint state info from Baxter ROS topic
  68. * \param
  69. */
  70. void stateCallback(const sensor_msgs::JointStateConstPtr& msg);
  71. /**
  72. * \brief Copy the joint state message into our hardware interface datastructures
  73. */
  74. void read( sensor_msgs::JointStateConstPtr &state_msg );
  75. /**
  76. * \brief Publish our hardware interface datastructures commands to Baxter hardware
  77. */
  78. void write(ros::Duration elapsed_time);
  79. /**
  80. * \brief Check if the cuff manual control button is squeezed.
  81. * \param msg - the state of the end effector cuff
  82. */
  83. //void cuffSqueezedCallback(const baxter_core_msgs::DigitalIOStateConstPtr& msg);
  84. /**
  85. * \brief This is called when Baxter is disabled, so that we can update the desired positions
  86. */
  87. void robotDisabledCallback();
  88. /**
  89. * \brief inform the trajectory controller to update its setpoint
  90. */
  91. void publishCurrentLocation();
  92. };
  93. } // namespace
  94. #endif




arm_hardware_interface.cpp



  1. #include <zzz_arm_2_hardware/arm_hardware_interface.h>
  2. #include <angles/angles.h>
  3. #include <urdf_parser/urdf_parser.h>
  4. #include <joint_limits_interface/joint_limits_urdf.h>
  5. #include <joint_limits_interface/joint_limits_rosparam.h>
  6. #include <pluginlib/class_list_macros.h>
  7. #include <zzz_arm_2_control_driver_msgs/joint_msg.h>
  8. namespace zzz_arm_2_control
  9. {
  10. using namespace hardware_interface;
  11. ArmHardwareInterface::ArmHardwareInterface(const std::string &arm_name, double loop_hz)
  12. : ArmInterface(arm_name, loop_hz),
  13. cuff_squeezed_previous(false)
  14. {
  15. // Populate joints in this arm
  16. /*joint_names_.push_back(arm_name_+"_e0");
  17. ...*/
  18. joint_names_.push_back("shoulder_zhuan_joint");
  19. joint_names_.push_back("upper_arm_joint");
  20. joint_names_.push_back("fore_arm_joint");
  21. joint_names_.push_back("hand_wan_joint");
  22. joint_names_.push_back("hand_zhuan_joint");
  23. //joint_names_.push_back("finger_1_joint");
  24. //joint_names_.push_back("finger_2_joint");
  25. n_dof_ = joint_names_.size();
  26. // Resize vectors
  27. joint_position_.resize(n_dof_);
  28. joint_velocity_.resize(n_dof_);
  29. joint_effort_.resize(n_dof_);
  30. joint_position_command_.resize(n_dof_);
  31. joint_effort_command_.resize(n_dof_);
  32. joint_velocity_command_.resize(n_dof_);
  33. //output_msg_.command.resize(n_dof_);
  34. //output_msg_.names.resize(n_dof_);
  35. trajectory_command_msg_.joint_names.resize(n_dof_);
  36. joint_id_to_joint_states_id_.resize(n_dof_);
  37. for (std::size_t i = 0; i < n_dof_; ++i)
  38. {
  39. joint_position_[i] = 0.0;
  40. joint_velocity_[i] = 0.0;
  41. joint_effort_[i] = 0.0;
  42. joint_position_command_[i] = 0.0;
  43. joint_effort_command_[i] = 0.0;
  44. joint_velocity_command_[i] = 0.0;
  45. trajectory_command_msg_.joint_names[i] = joint_names_[i];
  46. }
  47. // Set trajectory to have two point
  48. trajectory_msgs::JointTrajectoryPoint single_pt;
  49. single_pt.positions.resize(n_dof_);
  50. single_pt.time_from_start = ros::Duration(0);
  51. trajectory_command_msg_.points.push_back(single_pt);
  52. trajectory_msgs::JointTrajectoryPoint single_pt2;
  53. single_pt2.positions.resize(n_dof_);
  54. single_pt2.time_from_start = ros::Duration(0.5);
  55. trajectory_command_msg_.points.push_back(single_pt2);
  56. }
  57. ArmHardwareInterface::~ArmHardwareInterface()
  58. {
  59. }
  60. bool ArmHardwareInterface::init(
  61. hardware_interface::JointStateInterface& js_interface,
  62. hardware_interface::EffortJointInterface& ej_interface,
  63. hardware_interface::VelocityJointInterface& vj_interface,
  64. hardware_interface::PositionJointInterface& pj_interface,
  65. int* joint_mode,
  66. sensor_msgs::JointStateConstPtr state_msg)
  67. {
  68. joint_mode_ = joint_mode;
  69. for (std::size_t i = 0; i < n_dof_; ++i)
  70. {
  71. // Create joint state interface for all joints
  72. js_interface.registerHandle(hardware_interface::JointStateHandle(
  73. joint_names_[i], &joint_position_[i], &joint_velocity_[i], &joint_effort_[i]));
  74. // Create position joint interface
  75. pj_interface.registerHandle(hardware_interface::JointHandle(
  76. js_interface.getHandle(joint_names_[i]),&joint_position_command_[i]));
  77. // Create velocity joint interface
  78. vj_interface.registerHandle(hardware_interface::JointHandle(
  79. js_interface.getHandle(joint_names_[i]),&joint_velocity_command_[i]));
  80. // Create effort joint interface
  81. ej_interface.registerHandle(hardware_interface::JointHandle(
  82. js_interface.getHandle(joint_names_[i]),&joint_effort_command_[i]));
  83. }
  84. // Start publishers
  85. /*pub_joint_command_ = nh_.advertise<baxter_core_msgs::JointCommand>("/robot/limb/"+arm_name_+
  86. "/joint_command",10);*/
  87. pub_trajectory_command_ = nh_.advertise<trajectory_msgs::JointTrajectory>("/robot/"+arm_name_+
  88. "_trajectory_controller/command",10);
  89. // Start subscribers
  90. /*cuff_squeezed_sub_ = nh_.subscribe<baxter_core_msgs::DigitalIOState>("/robot/digital_io/" +
  91. arm_name_ + "_lower_cuff/state",
  92. 1, &ArmHardwareInterface::cuffSqueezedCallback, this);
  93. */
  94. zzz_fake_joint_pub_ = nh_.advertise<sensor_msgs::JointState>("/move_group/fake_controller_joint_states", 1);
  95. joint_motor_pub_= nh_.advertise<zzz_arm_2_control_driver_msgs::joint_msg>("/arm_motors", 1000);
  96. // Make a mapping of joint names to indexes in the joint_states message
  97. for (std::size_t i = 0; i < n_dof_; ++i)
  98. {
  99. std::vector<std::string>::const_iterator iter = std::find(state_msg->name.begin(), state_msg->name.end(), joint_names_[i]);
  100. size_t joint_states_id = std::distance(state_msg->name.begin(), iter);
  101. if(joint_states_id == state_msg->name.size())
  102. {
  103. ROS_ERROR_STREAM_NAMED(arm_name_,"Unable to find joint " << i << " named " << joint_names_[i] << " in joint state message");
  104. }
  105. joint_id_to_joint_states_id_[i] = joint_states_id;
  106. ROS_DEBUG_STREAM_NAMED("arm_hardware_interface","Found joint " << i << " at " << joint_states_id << " named " << joint_names_[i]);
  107. }
  108. // Set the initial command values based on current state
  109. for (std::size_t i = 0; i < n_dof_; ++i)
  110. {
  111. joint_position_command_[i] = state_msg->position[joint_id_to_joint_states_id_[i]];
  112. // Pre-load the joint names into the output messages just once
  113. //output_msg_.names[i] = joint_names_[i];
  114. }
  115. // Position joint limits interface
  116. /* std::vector<std::string> cmd_handle_names = pj_interface.getNames();
  117. for (size_t i = 0; i < n_dof_; ++i)
  118. {
  119. const std::string name = cmd_handle_names[i];
  120. JointHandle cmd_handle = pj_interface.getHandle(name);
  121. using namespace joint_limits_interface;
  122. boost::shared_ptr<const urdf::Joint> urdf_joint = urdf_model->getJoint(name);
  123. JointLimits limits;
  124. SoftJointLimits soft_limits;
  125. if (!getJointLimits(urdf_joint, limits) || !getSoftJointLimits(urdf_joint, soft_limits))
  126. {
  127. ROS_WARN_STREAM("Joint limits won't be enforced for joint '" << name << "'.");
  128. }
  129. else
  130. {
  131. jnt_limits_interface_.registerHandle(
  132. PositionJointSoftLimitsHandle(cmd_handle, limits, soft_limits));
  133. ROS_DEBUG_STREAM("Joint limits will be enforced for joint '" << name << "'.");
  134. }
  135. }*/
  136. // PID controllers
  137. pids_.resize(n_dof_);
  138. for (size_t i = 0; i < n_dof_; ++i)
  139. {
  140. ros::NodeHandle joint_nh(nh_, "gains/" + joint_names_[i]);
  141. if (!pids_[i].init(joint_nh))
  142. {
  143. ROS_WARN_STREAM("PID data err 'gains/" << joint_names_[i] << "'.");
  144. //return false;
  145. }
  146. }
  147. ROS_INFO_NAMED(arm_name_, "Loaded zzz_arm_2_hardware_interface.");
  148. return true;
  149. }
  150. void ArmHardwareInterface::read( sensor_msgs::JointStateConstPtr &state_msg )
  151. {
  152. // Copy state message to our datastructures
  153. //ROS_INFO_STREAM_NAMED("arm_hardware_interface","n_dof_="<<n_dof_);
  154. for (std::size_t i = 0; i < n_dof_; ++i)
  155. {
  156. //ROS_INFO_STREAM_NAMED("arm_hardware_interface","Joint " << i << "("<< joint_names_[i] << ") -> " << joint_id_to_joint_states_id_[i] << " position= " << state_msg->position[joint_id_to_joint_states_id_[i]]);
  157. std::size_t sp=state_msg->position.size();
  158. std::size_t sv=state_msg->velocity.size();
  159. std::size_t se=state_msg->effort.size();
  160. joint_position_[i] = sp>joint_id_to_joint_states_id_[i]?state_msg->position[joint_id_to_joint_states_id_[i]]:0.0;
  161. joint_velocity_[i] = sv>joint_id_to_joint_states_id_[i]?state_msg->velocity[joint_id_to_joint_states_id_[i]]:0.0;
  162. joint_effort_[i] = se>joint_id_to_joint_states_id_[i]?state_msg->effort[joint_id_to_joint_states_id_[i]]:0.0;
  163. }
  164. }
  165. void ArmHardwareInterface::write(ros::Duration elapsed_time)
  166. {
  167. // Enforce joint limits
  168. //jnt_limits_interface_.enforceLimits(elapsed_time);
  169. zzz_arm_2_control_driver_msgs::joint_msg joint_motor_msg;
  170. // Compute and send commands
  171. sensor_msgs::JointState joint_state_msg;
  172. joint_state_msg.name.resize(n_dof_);
  173. joint_state_msg.position.resize(n_dof_);
  174. joint_state_msg.header.stamp = ros::Time::now();
  175. for (size_t i = 0; i < n_dof_; ++i)
  176. {
  177. //const double error = joint_position_command_[i] - joint_position_[i];
  178. //const double effort = pids_[i].computeCommand(error, elapsed_time);
  179. joint_motor_msg.id=i;
  180. joint_motor_msg.r=joint_position_command_[i];
  181. joint_motor_pub_.publish(joint_motor_msg);
  182. //joint_state_msg.name[i] =joint_names_[i];
  183. //joint_state_msg.position[i] = joint_position_command_[i] ;
  184. //sim_joints_[i]->SetForce(0u, effort);
  185. }
  186. //zzz_fake_joint_pub_.publish(joint_state_msg);
  187. ros::spinOnce();
  188. //ROS_INFO("run write" );
  189. // Send commands to baxter in different modes
  190. /*switch (*joint_mode_)
  191. {
  192. case hardware_interface::MODE_POSITION:
  193. output_msg_.command = joint_position_command_;
  194. output_msg_.mode = baxter_core_msgs::JointCommand::POSITION_MODE;
  195. break;
  196. case hardware_interface::MODE_VELOCITY:
  197. output_msg_.command = joint_velocity_command_;
  198. output_msg_.mode = baxter_core_msgs::JointCommand::VELOCITY_MODE;
  199. break;
  200. case hardware_interface::MODE_EFFORT:
  201. output_msg_.command = joint_effort_command_;
  202. output_msg_.mode = baxter_core_msgs::JointCommand::TORQUE_MODE;
  203. break;
  204. }*/
  205. // Publish
  206. //pub_joint_command_.publish(output_msg_);
  207. }
  208. /*
  209. void ArmHardwareInterface::cuffSqueezedCallback(const baxter_core_msgs::DigitalIOStateConstPtr& msg)
  210. {
  211. // Check if button is pressed
  212. if( msg->state == 1 )
  213. {
  214. cuff_squeezed_previous = true;
  215. }
  216. else // button not pressed
  217. {
  218. if ( cuff_squeezed_previous )
  219. {
  220. publishCurrentLocation();
  221. }
  222. cuff_squeezed_previous = false;
  223. }
  224. }
  225. */
  226. void ArmHardwareInterface::publishCurrentLocation()
  227. {
  228. // Publish this new trajectory just once, on cuff release
  229. ROS_INFO_STREAM_NAMED(arm_name_, "Sent updated trajectory to trajectory controller");
  230. // Update the trajectory message with the current positions
  231. for (std::size_t i = 0; i < n_dof_; ++i)
  232. {
  233. trajectory_command_msg_.points[0].positions[i] = joint_position_[i];
  234. trajectory_command_msg_.points[1].positions[i] = joint_position_[i];
  235. }
  236. // Send a trajectory
  237. pub_trajectory_command_.publish(trajectory_command_msg_);
  238. }
  239. void ArmHardwareInterface::robotDisabledCallback()
  240. {
  241. publishCurrentLocation();
  242. }
  243. } // namespace





zzz_arm_2_hardware_interface.h

  1. #ifndef BAXTER_CONTROL__BAXTER_HARDWARE_INTERFACE_
  2. #define BAXTER_CONTROL__BAXTER_HARDWARE_INTERFACE_
  3. // Boost
  4. #include <boost/shared_ptr.hpp>
  5. // ROS
  6. #include <ros/ros.h>
  7. // ros_control
  8. #include <controller_manager/controller_manager.h>
  9. #include <hardware_interface/joint_command_interface.h>
  10. #include <hardware_interface/joint_state_interface.h>
  11. //#include <hardware_interface/joint_mode_interface.h>
  12. #include <hardware_interface/robot_hw.h>
  13. // Baxter
  14. //#include <zzz_arm_2_hardware/baxter_utilities.h>
  15. #include <zzz_arm_2_hardware/arm_interface.h>
  16. #include <zzz_arm_2_hardware/arm_hardware_interface.h>
  17. //#include <zzz_arm_2_hardware/arm_simulator_interface.h>
  18. namespace zzz_arm_2_control
  19. {
  20. static const double NUM_BAXTER_JOINTS = 5;
  21. class ZZZArm2HardwareInterface : public hardware_interface::RobotHW
  22. {
  23. private:
  24.   // Node Handles
  25.   ros::NodeHandle nh_; // no namespace
  26.   // Timing
  27.   ros::Duration control_period_;
  28.   ros::Time last_sim_time_ros_;
  29.   ros::Duration elapsed_time_;
  30.   double loop_hz_;
  31.   // Interfaces
  32.   hardware_interface::JointStateInterface    js_interface_;
  33.   //hardware_interface::JointModeInterface     jm_interface_;
  34.   hardware_interface::EffortJointInterface   ej_interface_;
  35.   hardware_interface::VelocityJointInterface vj_interface_;
  36.   hardware_interface::PositionJointInterface pj_interface_;
  37.   // baxter helper
  38.   //baxter_control::BaxterUtilities baxter_util_;
  39.   // sub-hardware interfaces
  40.   ArmInterfacePtr right_arm_hw_;
  41.   //ArmInterfacePtr left_arm_hw_;
  42.   boost::shared_ptr<controller_manager::ControllerManager> controller_manager_;
  43.   ros::Timer non_realtime_loop_;
  44.   bool in_simulation_;
  45.   // Which joint mode are we in
  46.   int joint_mode_;
  47.   // Buffer of joint states to share between arms
  48.   sensor_msgs::JointStateConstPtr state_msg_;
  49.   ros::Time state_msg_timestamp_;
  50.   // Subscriber
  51.   ros::Subscriber sub_joint_state_;
  52. public:
  53.   /**
  54.    * \brief Constructor/Descructor
  55.    */
  56.   ZZZArm2HardwareInterface(bool in_simulation);
  57.   ~ZZZArm2HardwareInterface();
  58.   /**
  59.    * \brief Checks if the state message from Baxter is out of date
  60.    * \return true if expired
  61.    */
  62.   bool stateExpired();
  63.   void stateCallback(const sensor_msgs::JointStateConstPtr& msg);
  64.   void update(const ros::TimerEvent& e);
  65. };
  66. } // namespace
  67. #endif

zzz_arm_2_hardware_interface.cpp

  1. #include <zzz_arm_2_hardware/zzz_arm_2_hardware_interface.h>
  2. namespace zzz_arm_2_control
  3. {
  4. ZZZArm2HardwareInterface::ZZZArm2HardwareInterface(bool in_simulation)
  5. : in_simulation_(in_simulation),
  6. joint_mode_(1),
  7. loop_hz_(75)//controller update speed
  8. {
  9. if( in_simulation_ )
  10. {
  11. ROS_INFO_STREAM_NAMED("hardware_interface","Running in simulation mode");
  12. //right_arm_hw_.reset(new zzz_arm_2_control::ArmSimulatorInterface("right",loop_hz_));
  13. //left_arm_hw_.reset(new zzz_arm_2_control::ArmSimulatorInterface("left",loop_hz_));
  14. }
  15. else
  16. {
  17. ROS_INFO_STREAM_NAMED("hardware_interface","Running in hardware mode");
  18. right_arm_hw_.reset(new zzz_arm_2_control::ArmHardwareInterface("right",loop_hz_));
  19. //left_arm_hw_.reset(new zzz_arm_2_control::ArmHardwareInterface("left",loop_hz_));
  20. }
  21. // Set the joint mode interface data
  22. //jm_interface_.registerHandle(hardware_interface::JointModeHandle("joint_mode", &joint_mode_));
  23. // Start the shared joint state subscriber
  24. sub_joint_state_ = nh_.subscribe<sensor_msgs::JointState>("/robot/joint_states", 1,
  25. &ZZZArm2HardwareInterface::stateCallback, this);
  26. // Wait for first state message to be recieved if we are not in simulation
  27. if (!in_simulation_)
  28. {
  29. // Loop until we find a joint_state message from Baxter
  30. do
  31. {
  32. // Loop until we get our first joint_state message
  33. while(ros::ok() && state_msg_timestamp_.toSec() == 0)
  34. {
  35. ROS_INFO_STREAM_NAMED("hardware_interface","Waiting for first state message to be recieved");
  36. ros::spinOnce();
  37. ros::Duration(0.25).sleep();
  38. }
  39. } while (state_msg_->name.size() < NUM_BAXTER_JOINTS);
  40. }
  41. // Initialize right arm
  42. right_arm_hw_->init(js_interface_, ej_interface_, vj_interface_, pj_interface_, &joint_mode_, state_msg_);
  43. //left_arm_hw_->init(js_interface_, ej_interface_, vj_interface_, pj_interface_, &joint_mode_, state_msg_);
  44. // Register interfaces
  45. registerInterface(&js_interface_);
  46. //registerInterface(&jm_interface_);
  47. registerInterface(&ej_interface_);
  48. registerInterface(&vj_interface_);
  49. registerInterface(&pj_interface_);
  50. // Enable baxter
  51. /*bool enabled = false;
  52. while(!enabled)
  53. {
  54. if( !baxter_util_.enableBaxter() )
  55. {
  56. ROS_WARN_STREAM_NAMED("hardware_interface","Unable to enable Baxter, retrying...");
  57. ros::Duration(0.5).sleep();
  58. ros::spinOnce();
  59. }
  60. else
  61. {
  62. enabled = true;
  63. }
  64. }
  65. */
  66. // Set callback for Baxter being disabled
  67. //baxter_util_.setDisabledCallback(boost::bind( &ArmInterface::robotDisabledCallback, right_arm_hw_ ));
  68. //baxter_util_.setDisabledCallback(boost::bind( &ArmInterface::robotDisabledCallback, left_arm_hw_ ));
  69. // Create the controller manager
  70. ROS_DEBUG_STREAM_NAMED("hardware_interface","Loading controller_manager");
  71. controller_manager_.reset(new controller_manager::ControllerManager(this, nh_));
  72. ros::Duration update_freq = ros::Duration(1.0/loop_hz_);
  73. non_realtime_loop_ = nh_.createTimer(update_freq, &ZZZArm2HardwareInterface::update, this);
  74. ROS_INFO_NAMED("hardware_interface", "Loaded baxter_hardware_interface.");
  75. }
  76. ZZZArm2HardwareInterface::~ZZZArm2HardwareInterface()
  77. {
  78. //baxter_util_.disableBaxter();
  79. }
  80. bool ZZZArm2HardwareInterface::stateExpired()
  81. {
  82. // Check that we have a non-expired state message
  83. // \todo lower the expiration duration
  84. if( ros::Time::now() > state_msg_timestamp_ + ros::Duration(STATE_EXPIRED_TIMEOUT)) // check that the message timestamp is no older than 1 second
  85. {
  86. ROS_WARN_STREAM_THROTTLE_NAMED(1,"hardware_interface","State expired. Last recieved state " << (ros::Time::now() - state_msg_timestamp_).toSec() << " seconds ago." );
  87. return true;
  88. }
  89. return false;
  90. }
  91. void ZZZArm2HardwareInterface::stateCallback(const sensor_msgs::JointStateConstPtr& msg)
  92. {
  93. //ROS_INFO("size=%d",msg->name.size());
  94. // Check if this message has the correct number of joints
  95. if( msg->name.size() < NUM_BAXTER_JOINTS )
  96. {
  97. return;
  98. }
  99. // Copy the latest message into a buffer
  100. state_msg_ = msg;
  101. state_msg_timestamp_ = ros::Time::now();
  102. }
  103. void ZZZArm2HardwareInterface::update(const ros::TimerEvent& e)
  104. {
  105. //ROS_INFO("update");
  106. // Check if state msg from Baxter is expired
  107. if( !in_simulation_ && stateExpired() )
  108. return;
  109. elapsed_time_ = ros::Duration(e.current_real - e.last_real);
  110. // Input
  111. right_arm_hw_->read(state_msg_);
  112. //left_arm_hw_->read(state_msg_);
  113. // Control
  114. controller_manager_->update(ros::Time::now(), elapsed_time_);
  115. // Output
  116. right_arm_hw_->write(elapsed_time_);
  117. //left_arm_hw_->write(elapsed_time_);
  118. }
  119. } // namespace
  120. int main(int argc, char** argv)
  121. {
  122. ROS_INFO_STREAM_NAMED("zzz_arm_2_hardware_interface","Starting hardware interface...");
  123. ros::init(argc, argv, "zzz_arm_2_hardware_interface");
  124. // Allow the action server to recieve and send ros messages
  125. ros::AsyncSpinner spinner(4);
  126. spinner.start();
  127. ros::NodeHandle nh;
  128. bool in_simulation = false;
  129. // Parse command line arguments
  130. for (std::size_t i = 0; i < argc; ++i)
  131. {
  132. if( std::string(argv[i]).compare("--simulation") == 0 )
  133. {
  134. ROS_INFO_STREAM_NAMED("main","zzz arm Hardware Interface in simulation mode");
  135. in_simulation = true;
  136. }
  137. }
  138. zzz_arm_2_control::ZZZArm2HardwareInterface zzzarm(in_simulation);
  139. //ros::spin();//error
  140. ros::waitForShutdown();
  141. ROS_INFO_STREAM_NAMED("hardware_interface","Shutting down.");
  142. return 0;
  143. }




ros_control 使用的yaml


  1. zzz_arm:
  2. zzz_arm_controller:
  3. type: position_controllers/JointTrajectoryController
  4. joints:
  5. - shoulder_zhuan_joint
  6. - upper_arm_joint
  7. - fore_arm_joint
  8. - hand_wan_joint
  9. - hand_zhuan_joint
  10. constraints:
  11. goal_time: &goal_time_constraint 10.0
  12. shoulder_zhuan_joint:
  13. goal: &goal_pos_constraint 0.5
  14. upper_arm_joint:
  15. goal: *goal_pos_constraint
  16. fore_arm_joint:
  17. goal: *goal_pos_constraint
  18. hand_wan_joint:
  19. goal: *goal_pos_constraint
  20. hand_zhuan_joint:
  21. goal: *goal_pos_constraint
  22. zzz_grapper_controller:
  23. type: position_controllers/JointTrajectoryController
  24. joints:
  25. - finger_1_joint
  26. - finger_2_joint
  27. constraints:
  28. goal_time: *goal_time_constraint
  29. finger_1_joint:
  30. goal: *goal_pos_constraint
  31. finger_2_joint:
  32. goal: *goal_pos_constraint
  33. # Publish all joint states -----------------------------------
  34. joint_state_controller:
  35. type: joint_state_controller/JointStateController
  36. publish_rate: 50
  37. gains:
  38. shoulder_zhuan_joint: {p: 3.0, i: 0.01, d: 1.1, i_clamp: 1.0}
  39. upper_arm_joint: {p: 3.0, i: 0.01, d: 1.1, i_clamp: 1.0}
  40. fore_arm_joint: {p: 3.0, i: 0.01, d: 1.1, i_clamp: 1.0}
  41. hand_wan_joint: {p: 3.0, i: 0.01, d: 1.1, i_clamp: 1.0}
  42. hand_zhuan_joint: {p: 3.0, i: 0.01, d: 1.1, i_clamp: 1.0}
  43. finger_1_joint: {p: 3.0, i: 0.01, d: 1.0, i_clamp: 1.0}
  44. finger_2_joint: {p: 3.0, i: 0.01, d: 1.0, i_clamp: 1.0}







moveit使用的yaml

controller_list:
  - name: zzz_arm/zzz_arm_controller
    action_ns: follow_joint_trajectory
    type: FollowJointTrajectory
    default: true
    joints:
      - shoulder_zhuan_joint
      - upper_arm_joint
      - fore_arm_joint
      - hand_wan_joint
      - hand_zhuan_joint
  - name: zzz_arm/zzz_grapper_controller
    action_ns: follow_joint_trajectory
    type: FollowJointTrajectory
    default: true
    joints:
      - finger_1_joint
      - finger_2_joint





launch 调用controller_manager 来启动 controllers

   
  1. <!-- Load the default controllers -->
  2. <node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
  3. output="screen" args="zzz_arm_controller zzz_grapper_controller
  4. joint_state_controller
  5. " />




可视化查看 controllers情况
sudo apt-get install ros-kinetic-rqt-controller-manager

zzz@zzz-ubuntu:~/rostest$ rosrun rqt_controller_manager rqt_controller_manager
qt_gui_main() found no plugin matching "rqt_controller_manager

问题出在 qt 的缓存没有更新安装插件。解决办法:

    $ rm ~/.config/ros.org/rqt_gui.ini  
    $ rqt



错误
Spinner Monitor: single-treaded spinner after multi-threaded ones

原因
  1. ros::AsyncSpinner spinner(4); // Use 4 threads
  2. spinner.start();
  3. //ros::spin();//error写成这样不知到作者是怎么编译成功的。反正我这里是过不去。


解决
http://wiki.ros.org/roscpp/Overview/Callbacks%20and%20Spinning

  1. ros::AsyncSpinner spinner(4); // Use 4 threads
  2. spinner.start();
  3. ros::waitForShutdown();




controller spawner coudn't find the expected controller_manager ROS interface
注意ns设置

zzz_arm_2_control_driver包下创建的joint_msg,包内节点使用没任何问题。
在另外的包引用
#include <zzz_arm_2_control_driver/joint_msg.h>
出现错误
ros fatal error: xxx/xxx.h: No such file or directory
以为是缺少配置
  1. <build_depend>zzz_arm_2_control_driver</build_depend>
  2. <run_depend>zzz_arm_2_control_driver</run_depend>

find_package(catkin REQUIRED COMPONENTS 
zzz_arm_2_control_driver
)


添加了又出现新的错误
ros The library is neither a target nor built...
did you find_package() it before the subdirectory containing its code is included?
半天无解




只好新建一个只包含joint_msg 的包zzz_arm_2_control_driver_msgs
其它包引用
  1. <build_depend>zzz_arm_2_control_driver_msgs</build_depend>
  2. <run_depend>zzz_arm_2_control_driver_msgs</run_depend>



find_package(catkin REQUIRED COMPONENTS
zzz_arm_2_control_driver_msgs
)



#include <zzz_arm_2_control_driver_msgs/joint_msg.h>


编译通过,水平菜真是不知道哪里有问题。
以后msg单独建包编译吧,有问题也能一目了然。



usb串口又忘了权限报错
terminate called after throwing an instance of 'boost::exception_detail::clone_impl
解决
sudo chmod 666 /dev/ttyUSB0




controller is taking too long to execute trajectory
舵机通信速度会影响 controller 的执行
controller update速度过快或者与舵机通信(joint_states 更新)速度过慢
controller就认为机器关节运动速度达不到要求(太慢甚至会认为没有执行动作)导致规划轨迹执行失败。


update速率根据实际情况计算(以下为不包括延时处理及等待时间的理论值,实际测试controller update在10hz左右为好)
波特率115200,每秒有11520字节被传送
通信协议
发送
位置控制#000P1500T1000!(15byte)
位置回读#000PRAD!(9byte)
接收
回读信息#000P1500!(10byte)
发送字节数计算 15+9=24 ,24×6(个舵机)=144byte
带宽全占满时是11520/144=80hz
串口joint_states更新频率controller update频率都应该匹配这个80hz

(考虑位置控制不是每次都发送因此joint_states更新频率可以适当高一点(100),考虑到ros消息非实时性controller update可以适当低一点(75))


高手用ros_control驱动 baxter
我用ros_control驱动低端的舵机手臂,是不是有杀鸡用牛刀的感觉?

好吧,还是老话,走自己的路让别人说去吧。


hello,baxter!




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

闽ICP备14008679号