ROS驱动珞石机器人


前言

最近因为项目需要用到珞石机器人,找了一圈终于在gitee上找到了(https://gitee.com/kipochen_uestc/rokae_ros_pkg),但是由于我机器人xCore的版本不兼容(xCore >= v2.1.0.15),所以在运行时报错,然后我下了一个低版本的SDK,并修改了相关驱动部分的代码,解决了由于SDK版本而存在的一些问题。

一、修改后的版本

  1. 测试的环境:ubuntu20.04
  2. 修改后的项目资源:https://github.com/ILMnk12/rokae_ros.git
  3. 测试所使用到的机器人型号:ER7
    注意:rokae_xMateER7_moveit_config、是笔者自己配置的,已经在实际机器人测试过的,其他的moveit包可能需要根据自己需要进行修改。

二、使用步骤

1.引入库

  1. 这块基于这个开源项目保持一致安装
安装ubuntu 20.04
安装 ROS Noetic 版本;(内部测试可参考一键安装方法)
安装 Moveit 以及编译工具包;
安装其他所需要的依赖包(如已安装可跳过):
sudo apt-get install ros-noetic-joint-state-publisher-gui
sudo apt-get install ros-noetic-ros-control ros-noetic-ros-controllers
sudo apt install ros-noetic-pilz-industrial-motion-planner
sudo apt-get install ros-noetic-rqt-joint-trajectory-controller
sudo apt-get install ros-noetic-industrial-core

2.使用方法

  1. 下载包
git clone https://github.com/ILMnk12/rokae_ros.git

  1. 将src文件夹下的包复制到自己的工作空间中

在这里插入图片描述

  1. 在自己的工作空间路径下执行catkin_make编译
  2. 使用roslaunch开始控制机器人
roslaunch rokae_bringup xMateER7_control.launch robot_ip:=192.168.0.160 local_ip:=192.168.0.130

三、主要修改的地方

  1. sdk部分的修改
    主要是将rokae_hardware/sdk/include/下的头文件,以及将rokae_hardware/sdk/lib/下的库文件用xCoreSDK-v0.3.3下的头文件和库文件进行替换,并对rokae_hardware下的CMakeLists.txt文件做了如下修改
add_library(libxCoreSDK SHARED IMPORTED)
set_target_properties(libxCoreSDK 
                      PROPERTIES IMPORTED_LOCATION ${CMAKE_CURRENT_SOURCE_DIR}/sdk/lib/libxCoreSDK.a)

add_library(libxMateModel SHARED IMPORTED)
set_target_properties(libxMateModel 
                      PROPERTIES IMPORTED_LOCATION ${CMAKE_CURRENT_SOURCE_DIR}/sdk/lib/libxMateModel.a)

  1. 代码部分的修改
    对rokae_hardware/include/rokae_hardware.h下的代码做了如下修改
 if (joint_position_controller_running_)
 {       if(times_loop_==0){

             sleep(5);
             times_loop_++;
         }
         rci_->updateRobotState();
         std::function<rokae::JointPosition()> callback2 = std::bind(&RokaeHardwareInterface::callback, this);
         rokae::JointPosition joints_value=callback2();
         rci_->setControlLoop(callback2, 0, true);
         // ROS_INFO_STREAM("PVI2");
         rci_->startLoop(false); 
         // rci_->stopMove();

 }
rokae::JointPosition callback() 
{

    // times_loop_ ++;
    // ROS_INFO_STREAM(times_loop_);
    rci_->updateRobotState();
    rokae::JointPosition jcmd(num_joints_);
    for (size_t i = 0; i < num_joints_; i++)
    {
        jcmd.joints[i] = joint_position_command_[i];

    }
   
    this->time_us2 = time_us1;
    this->time_us1 = getLocalTimeUs();
    
    usleep(50);
    //   ROS_INFO("time");
    //  ROS_INFO_STREAM(time_us1 - time_us2);/

    return jcmd;
}
 for (auto &controller_it : start_list)
 {
     std::cout << "resource controllers check" << std::endl;
     for (auto &resource_it : controller_it.claimed_resources)
     {
         if (checkControllerClaims(resource_it.resources))
         {
             if (resource_it.hardware_interface == "hardware_interface::PositionJointInterface")
             {
                 joint_velocity_controller_running_ = false;
                 joint_torque_controller_running_ = false;
                 joint_position_controller_running_ = true;
                 if (joint_position_controller_running_)
                 {
                     // rci_->stopMove();
                     rci_->startMove(rokae::RtControllerMode::jointPosition);

                 }
             }
             else if (resource_it.hardware_interface == "hardware_interface::VelocityJointInterface")
             {
                 joint_position_controller_running_ = false;
                 joint_torque_controller_running_ = false;
                 joint_velocity_controller_running_ = true;
                 if (joint_velocity_controller_running_)
                 {
                     //rci_->stopMove();
                     rci_->startMove(rokae::RtControllerMode::jointPosition);
                 }
             }
             else if (resource_it.hardware_interface == "hardware_interface::EffortJointInterface")
             {
                 joint_position_controller_running_ = false;
                 joint_velocity_controller_running_ = false;
                 joint_torque_controller_running_ = true;
                 if (joint_torque_controller_running_)
                 {
                    // rci_->stopMove();
                     rci_->startMove(rokae::RtControllerMode::torque);
                 }
             }
         }
     }
 }

四、解决的问题

原因说明(自己推测的)
(1).机器人在上电时,真实机器人状态和仿真环境中的状态未完全同步,所以我加入了一些延时来解决这一问题

  if(times_loop_==0){

                        sleep(5);
                        times_loop_++;
                    }

(2).机器人在实际运行时候报错

[INFO] [1733485610.125805]: Started controllers: joint_state_controller, position_joint_trajectory_controller
terminate called after throwing an instance of 'rokae::RealtimeMotionException'
  what():  实时模式异常: 运动错误: 轴空间运动超关节限位或轨迹不连续; 或速度/加速度超过阈值, 请检查客户端规划轨迹. (3-kActualJointVelocityLimitsViolation)
[rokae_hardware-2] process has died [pid 54850, exit code -11, cmd /home/ubuntu/caktin_ws/devel/lib/rokae_hardware/rokae_hardware __name:=rokae_hardware __log:=/home/ubuntu/.ros/log/200f09c2-b79d-11ef-a535-eba93dc3bfef/rokae_hardware-2.log].
log file: /home/ubuntu/.ros/log/200f09c2-b79d-11ef-a535-eba93dc3bfef/rokae_hardware-2*.log

通过和客服沟通,我在rci_->setControlLoop(callback2, 0, true);之前以及在回调函数中都加入了 **rci_->updateRobotState();**更新机器人状态,解决了这一问题。

五、目前还存在的问题

由于笔者能力有限,所以在测试的过程中发现在用roslaunch启动控制后,如果终止程序,然后再启动就无法控制机器人,只能通过机器人断电,然后再上电的方式解决目前这个问题还在研究中。

评论 1
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值