【Coppeliasim4.3】基于remoteApi的C++ 示教器操作仿真器中的UR10

b67ce436e70261e9b83d98f65503fce2.png

C++示教器

8f1341696b9127a50c651c8e838931e3.png

场景截图

视频演示

笔记:

一、用于 VS 2022 .NET 框架的 C++ Windows 窗体

通过用 C++ 编写的 Windows 窗体项目扩展 Visual Studio 2022 。此类项目创建的应用程序具有图形用户界面。它们基于 .NET Framework。您可以使用所有常见的 Windows 控件,如按钮、菜单、文本框等。

与传统 C++ 程序的主要区别在于,它不是使用控制台进行用户交互

cout << "Hello world" << endl;

您可以使用 Windows 控件,例如 TextBox

textBox1->AppendText("Hello World");

安装扩展 https://marketplace.visualstudio.com/items?itemName=RichardKaiser.cppclrwinf

0d46ed7dcd0900384aed7676bfce9854.png

f317b7512990686d6309864c123e893d.png

创建项目时选择CppCLR_WinFormsProject

二、coppeliasim类是对remoteApi的封装,可以操作机器人、获取传感器数据.通过调用脚本函数进行任何可能的操作。

.h文件:

#pragma once
/*
NON_MATLAB_PARSING
MAX_EXT_API_CONNECTIONS=255
_CRT_SECURE_NO_WARNINGS
DO_NOT_USE_SHARED_MEMORY
*/




#include <stdlib.h>
#include <iostream>
#include <windows.h>
#include <stdio.h>
#include <process.h>
#include <fstream>
//#include <msclr\marshal_cppstd.h>


extern "C" {
#include "extApi.h"
//#include "simConst.h"
}


using namespace std;


#define RAD_TO_DEG (180/3.141592)
#define DEG_TO_RAD (3.141592/180)






//检索全局句柄 Retrieve global handle;
class CoppeliaSim {
public:
  bool connected;//连接状态
  int clientID;//客户端id


public:
  bool connect(int port);//连接
  void disconnect(int clientID);//断开连接
  void startSimulation();//开始仿真
  void stopSimulation();//停止仿真


};


//类:机器人 Class Robot
class CoppeliaRobot: public CoppeliaSim{
public:
  void init(string robot_name);//初始化:机器人名称
  void setPosition(float pos[6], bool wait);//设置位置
  void setPosition(float x, float y, float z, float w, float p, float r, bool wait);//设置tcp位置 wait
  void setPosition(float x, float y, float z, float w, float p, float r);//设置tcp位置  
  void setJointPosition(float joint[6], bool wait);//设置关节位置
  void setJointPosition(float J1, float J2, float J3, float J4, float J5, float J6);//设置所有关节位置
  void setJointPosition(int num, float tetha);  // 设置单关节位置 Set single joint position  


  void setPosition2(float pos[6]);        //直接设定物体位置(无速度控制) Direct set object position (no speed control)
  void readCurrentJointPos(float joint_pos[6]);//读取当前关节位置
  void readObjectPosition(string object_name, float current_pos[6]);//读取对象位置
  void enableIk(bool enable);//启用IK
  bool isMoving();//移动中
  void setSpeed(float vel, float ang_vel);//设置速度
  void gripperCatch();//夹爪抓取
  void gripperRelease();//夹爪释放




  void readPosition(float pos[6]);//读取tcp位置
  void readForce(float force[6]);//读取六维力


  void getObjectMatrix(float M[4][4]);//获取对象位姿矩阵


public:
  int joint_handle[6];//机器人6个关节句柄
  int forceSensor_handle;//力传感器句柄
  simxChar * script_name;//脚本名称
  string scriptName;//脚本名


  //Ik Handle IK句柄
  int ikTargetHandle;//ik目标句柄
  int ikTipHandle;//ik  tip句柄
  int robotHandle;//机器人句柄
  int moving;//移动状态 
  int ftHandle;//力传感器句柄
  int targetPosHandle;//目标位置句柄


  float __force[3];//三维力
  float __torque[3];//三维力矩
  float __pos[3];//位置
  float __rot[3];//姿态


  int __cnt; //输出位置的数量 
  float* __position;//位置指针
  float* __jointpos;//关节位置指针


  simxUChar state;//力传感器状态
};


//类:力传感器 Class Force Sensor
class CoppeliaForce{
public:
  void init(int clientID, simxChar * obj_name);//初始化力传感器:获取其句柄
  void read(float force[6]);//读取六维力
private:
  int forceHandle;//力传感器句柄
  int clientID;//客户端id
};

.cpp文件:

#include "coppeliasim.h"
#include <windows.h>


// Connect to coppelia sim, defaulf port: 19997
/
bool CoppeliaSim::connect(int port)
{
  if (!connected) {
    simxFinish(-1);//最后一个要调用的函数
    this->clientID = simxStart((simxChar*)"127.0.0.1", port, true, true, 2000, 5);//连接服务器
    if (this->clientID != -1) {
      this->connected = true;
      printf("> CoppeliaSIM connection success! Client ID : %d \n", clientID);
      // Start simulation:
      //simxStartSimulation(clientID, simx_opmode_oneshot_wait);
      return true;
    }
    else {
      printf("> Simxstart failed!!! \n");
    }
  }
  else {
    printf("> CoppeliaSim already connected. Please disconnect first. \n");//已经连接
  }
  return false;
}





//断开与CoppeliaSim服务器的连接
void CoppeliaSim::disconnect(int clientID)
{
  this->connected = false;
  simxFinish(clientID);
}
// 开始仿真Start Simulation
void CoppeliaSim::startSimulation() {
  simxStartSimulation(clientID, simx_opmode_blocking);
}
//停止仿真
void CoppeliaSim::stopSimulation() {
  simxStopSimulation(clientID, simx_opmode_blocking);
}




// 力传感器初始化,获取其句柄 Force Sensor
void CoppeliaForce::init(int clientID, simxChar * obj_name)
{
  this->clientID = clientID;
  simxGetObjectHandle(this->clientID, obj_name, &forceHandle, simx_opmode_oneshot_wait);//获取力传感器句柄
  printf("__INFO___: Coppeliasim force sensor handle ID : %d \n", forceHandle);
}
//读取六维力:力和力矩
void CoppeliaForce::read(float force[6]) 
{
  simxUChar state;//状态
  float _torque[3] = {0 ,0 ,0 };//三维力矩
  float _force[3] = {0, 0, 0,};//三维力
  simxReadForceSensor(this->clientID, forceHandle, &state, _force, _torque, simx_opmode_continuous);//读取力传感器状态


  for (int i = 0; i < 3; i++) {
    force[i] = _force[i];
  }
  for (int i = 0; i < 3; i++) {
    force[i + 3] = _torque[i];
  }
//  printf("Force Data: %.3f  %.3f  %.3f \n", force[0], force[1], force[2]);
}










//机器人类  Robot Class
///
//启用IK
void CoppeliaRobot::enableIk(bool enable) 
{
  int dataSend;//要发送的数据
  if (enable) dataSend = 1;//启用ik,发送1
  else dataSend = 0;//不启用ik,发送0
  //调用脚本函数
  int result = simxCallScriptFunction(
    clientID,
    script_name,            // 关联对象脚本的名称the name of the associated obejct script
    sim_scripttype_childscript,      // 脚本的句柄 the handle of the script
    "enableIk",              // 函数名称 Function name
    1, &dataSend,              //输入的int数量,输入的int指针 inIntCnt, inInt
    0, NULL,            // inFloatCnt, inFloat
    0, NULL,              // inStringCnt, inString
    0, NULL,              // inBufferSize, inBuffer
    NULL, NULL,              // outIntCnt, outInt
    NULL, NULL,              // outFloatCnt, outFloat
    NULL, NULL,              // outStringCnt, outString
    NULL, NULL,              // outBufferSize, outBuffer
    simx_opmode_oneshot);//单次模式
}


// Robot initialization: retreive some handles:
//   
//机器人初始化:检索一些句柄:
void CoppeliaRobot::init(string robot_name) {
  string temp("/" + robot_name);
  scriptName = temp;
  string target_obj_name("./" + robot_name + "/ikTarget");//ik目标名称 字符串
  string tip_obj_name   ("./" + robot_name + "/ikTip");//iktip名称 字符串
  string ft_obj_name    ("./" + robot_name + "/force_sensor");//力传感器名称 字符串
  string targetPos_obj_name("./" + robot_name + "/targetPos");//目标位置对象名称


  simxGetObjectHandle(clientID, robot_name.c_str(), &robotHandle, simx_opmode_blocking);//获取机器人句柄
  simxGetObjectHandle(clientID, target_obj_name.c_str(), &ikTargetHandle, simx_opmode_blocking);//获取目标对象句柄
  simxGetObjectHandle(clientID, tip_obj_name.c_str(), &ikTipHandle, simx_opmode_blocking);//获取tip句柄
  simxGetObjectHandle(clientID, ft_obj_name.c_str(), &ftHandle, simx_opmode_blocking);//获取力传感器句柄
  simxGetObjectHandle(clientID, targetPos_obj_name.c_str(), &targetPosHandle, simx_opmode_blocking);//获取目标位置句柄


  cout << "\n\nSimulation properties:" << endl;
  cout << "Robot Handle: " << robotHandle << endl;
  cout << "ikTarget    : " << ikTargetHandle << endl;
  cout << "ikTip       : " << ikTipHandle << endl;
  cout << "Force Sensor: " << ftHandle << endl;


  //启动流数据事务:Start Stream data routine:
  simxReadForceSensor(clientID, ftHandle, &state, __force, __torque, simx_opmode_streaming);//获取力传感器数据
  simxGetIntegerSignal(clientID, "moving_status", &moving, simx_opmode_streaming);//获取整型信号  moving_status。


  //simxGetObjectPosition(clientID, ikTipHandle, robotHandle, __pos, simx_opmode_streaming);
  //simxGetObjectOrientation(clientID, ikTipHandle, robotHandle, __rot, simx_opmode_streaming);
  
  // 位置数据流 Stream position data:
  simxCallScriptFunction(
    clientID,
    scriptName.c_str(),          // the name of the associated obejct script  关联的对象脚本名
    sim_scripttype_childscript,      // the handle of the script 脚本类型:子脚本
    "remoteApi_getPosition",      // Function name  调用脚本的函数名remoteApi_getPosition
    0, NULL,              // inIntCnt, inInt
    0, NULL,              // inFloatCnt, inFloat
    0, NULL,              // inStringCnt, inString
    0, NULL,              // inBufferSize, inBuffer
    NULL, NULL,              // outIntCnt, outInt  
    &__cnt, &__position,        // outFloatCnt, outFloat //浮点数量,浮点数指针
    NULL, NULL,              // outStringCnt, outString
    NULL, NULL,              // outBufferSize, outBuffer
    simx_opmode_streaming);//流操作模式
  
  // 关节位置数据 Stream joint position data:
  simxCallScriptFunction(
    clientID,
    scriptName.c_str(),          // the name of the associated obejct script
    sim_scripttype_childscript,      // the handle of the script
    "remoteApi_getJointPosition",      // Function name  脚本的获取关节位置函数
    0, NULL,              // inIntCnt, inInt
    0, NULL,              // inFloatCnt, inFloat
    0, NULL,              // inStringCnt, inString
    0, NULL,              // inBufferSize, inBuffer
    NULL, NULL,              // outIntCnt, outInt
    &__cnt, &__position,        // outFloatCnt, outFloat
    NULL, NULL,              // outStringCnt, outString
    NULL, NULL,              // outBufferSize, outBuffer
    simx_opmode_streaming);


}


//读取力传感器数据
void CoppeliaRobot::readForce(float force[6]) {
  simxReadForceSensor(clientID, ftHandle, &state, __force, __torque, simx_opmode_buffer);
  for (int i = 0; i < 3; i++) {
    force[i] = __force[i];
    force[i + 3] = __torque[i];
  }
}




// 设置机械臂位置Set robot arm position:
// 
void CoppeliaRobot::setPosition(float pos[6], bool wait)
{
  setPosition(pos[0], pos[1], pos[2], pos[3], pos[4], pos[5]);


  if (wait){
    while (isMoving());
  }
}
//设置位置
void CoppeliaRobot::setPosition(float x, float y, float z, float w, float p, float r, bool wait)
{
  setPosition(x, y, z, w, p, r);
  if (wait) {
    while (isMoving());
  }
}
//设置tcp位置
void CoppeliaRobot::setPosition(float x, float y, float z, float w, float p, float r)
{
  //enableIk(true);        //启用IK模式 Enable IK mode


  float pos[6];
  pos[0] = x / 1000;      // meter
  pos[1] = y / 1000;      // meter
  pos[2] = z / 1000;      // meter
  pos[3] = w * DEG_TO_RAD;  // rad
  pos[4] = p * DEG_TO_RAD;  // rad
  pos[5] = r * DEG_TO_RAD;  // rad
  //调用脚本函数
  int result = simxCallScriptFunction(
    clientID,
    scriptName.c_str(),            // the name of the associated obejct script
    sim_scripttype_childscript,      // the handle of the script
    "remoteApi_movePosition",      // Function name  移动位置函数remoteApi_movePosition
    0, NULL,              // inIntCnt, inInt
    6, pos,                // inFloatCnt, inFloat
    0, NULL,              // inStringCnt, inString
    0, NULL,              // inBufferSize, inBuffer
    NULL, NULL,              // outIntCnt, outInt
    NULL, NULL,              // outFloatCnt, outFloat
    NULL, NULL,              // outStringCnt, outString
    NULL, NULL,              // outBufferSize, outBuffer
    simx_opmode_oneshot);//单次模式
}




//设置机器人关节位置 Set Robot Joint Position:
///
void CoppeliaRobot::setJointPosition(float joint[6], bool wait) {
  setJointPosition(joint[0], joint[1], joint[2], joint[3], joint[4], joint[5]);
  if(wait) while (isMoving());            // Wait moving 
}
void CoppeliaRobot::setJointPosition(float J1, float J2, float J3, float J4, float J5, float J6) 
{
  //enableIk(false);            // Enable Joint MODE


  float joint[6];
  joint[0] = J1 * (DEG_TO_RAD);
  joint[1] = J2 * (DEG_TO_RAD);
  joint[2] = J3 * (DEG_TO_RAD);
  joint[3] = J4 * (DEG_TO_RAD);
  joint[4] = J5 * (DEG_TO_RAD);
  joint[5] = J6 * (DEG_TO_RAD);


  int result = simxCallScriptFunction(
    clientID,
    scriptName.c_str(),            // the name of the associated obejct script
    sim_scripttype_childscript,      // the handle of the script
    "remoteApi_moveJointPosition",        // Function name
    0, NULL,              // inIntCnt, inInt
    6, joint,              // inFloatCnt, inFloat
    0, NULL,              // inStringCnt, inString
    0, NULL,              // inBufferSize, inBuffer
    NULL, NULL,              // outIntCnt, outInt
    NULL, NULL,              // outFloatCnt, outFloat
    NULL, NULL,              // outStringCnt, outString
    NULL, NULL,              // outBufferSize, outBuffer
    simx_opmode_oneshot);
}
//设置关节位置:调用脚本函数moveSingleJointPosition
void CoppeliaRobot::setJointPosition(int num, float tetha)
{
  enableIk(false);            // Enable Joint Mode
  float jointAngle = tetha * DEG_TO_RAD;
  int result = simxCallScriptFunction(
    clientID,
    scriptName.c_str(),            // the name of the associated obejct script
    sim_scripttype_childscript,      // the handle of the script
    "moveSingleJointPosition",      // Function name
    1, &num,              // inIntCnt, inInt
    1, &jointAngle,            // inFloatCnt, inFloat
    0, NULL,              // inStringCnt, inString
    0, NULL,              // inBufferSize, inBuffer
    NULL, NULL,              // outIntCnt, outInt
    NULL, NULL,              // outFloatCnt, outFloat
    NULL, NULL,              // outStringCnt, outString
    NULL, NULL,              // outBufferSize, outBuffer
    simx_opmode_oneshot_wait);


  while (isMoving());//等待到位?
}


//读取当前机器人关节位置 调用脚本函数:remoteApi_getJointPosition    Read Current Robot Joint Position:
void CoppeliaRobot::readCurrentJointPos(float joint_pos[6]) 
{
  int cnt;//6个关节
  float *jointData;//关节数据指针
  int* inData = nullptr;//
  int result = simxCallScriptFunction(
    clientID,
    scriptName.c_str(),            // the name of the associated obejct script
    sim_scripttype_childscript,      // the handle of the script
    "remoteApi_getJointPosition",    // Function name
    0, NULL,              // inIntCnt, inInt
    0, NULL,              // inFloatCnt, inFloat
    0, NULL,              // inStringCnt, inString
    0, NULL,              // inBufferSize, inBuffer
    NULL, NULL,            // outIntCnt, outInt
    &cnt, &jointData,          // outFloatCnt, outFloat  数量,关节数据
    NULL, NULL,              // outStringCnt, outString
    NULL, NULL,              // outBufferSize, outBuffer
    simx_opmode_buffer);
  if (jointData==NULL)
  {
    return;
  }
  try
  {
    for (int i = 0; i < 6; i++) {
      joint_pos[i] = jointData[i] * RAD_TO_DEG;
    }
  }
  catch (const std::exception& e)
  {
    //MessageBoxA(NULL,e.what(), "Warn", MB_OK);  //winuser.h  https://docs.microsoft.com/en-us/windows/win32/api/winuser/nf-winuser-messageboxa
  }


}




// Get robot moving status. Return TRUE if the robot is moving and
// return FALSE is robot is stop.
// 获取机器人移动状态。如果机器人正在移动并且返回 TRUE
// 返回 FALSE 是机器人停止。
bool CoppeliaRobot::isMoving() {
  Sleep(50);
  simxGetIntegerSignal(clientID, "moving_status", &moving, simx_opmode_buffer);//获取移动状态
  if (moving) return true;//1:移动中
  else return false;//0:未移动
}




//手臂机器人手抓 抓  Arm Robot Gripper Catch
void CoppeliaRobot::gripperCatch()
{
  int state = 0;//输入夹爪状态 0
  int result = simxCallScriptFunction(
    clientID,
    scriptName.c_str(),            // the name of the associated obejct script
    sim_scripttype_childscript,      // the handle of the script
    "remoteApi_setGripper",            // Function name
    1, &state,              // inIntCnt, inInt
    0, NULL,              // inFloatCnt, inFloat
    0, NULL,              // inStringCnt, inString
    0, NULL,              // inBufferSize, inBuffer
    NULL, NULL,              // outIntCnt, outInt
    NULL, NULL,              // outFloatCnt, outFloat
    NULL, NULL,              // outStringCnt, outString
    NULL, NULL,              // outBufferSize, outBuffer
    simx_opmode_oneshot);
}


//释放夹爪 Arm Robot Gripper Gripper Release
void CoppeliaRobot::gripperRelease()
{
  int state = 1;//释放夹爪:1
  int result = simxCallScriptFunction(
    clientID,
    scriptName.c_str(),            // the name of the associated obejct script
    sim_scripttype_childscript,      // the handle of the script
    "remoteApi_setGripper",            // Function name//调用脚本函数:remoteApi_setGripper
    1, &state,              // inIntCnt, inInt
    0, NULL,              // inFloatCnt, inFloat
    0, NULL,              // inStringCnt, inString
    0, NULL,              // inBufferSize, inBuffer
    NULL, NULL,              // outIntCnt, outInt
    NULL, NULL,              // outFloatCnt, outFloat
    NULL, NULL,              // outStringCnt, outString
    NULL, NULL,              // outBufferSize, outBuffer
    simx_opmode_oneshot);//单次调用模式
}


// Get Robot Tip Homogeneous Matrix:
/
//获取tip位姿矩阵
void CoppeliaRobot::getObjectMatrix(float M[4][4])
{
  int cnt;//12
  float *pData;//位姿矩阵数据
  int result = simxCallScriptFunction(
    clientID,
    scriptName.c_str(),            // the name of the associated obejct script
    sim_scripttype_childscript,      // the handle of the script
    "getObjectMatrix",            // Function name //获取tip位姿矩阵
    0, NULL,              // inIntCnt, inInt
    0, NULL,              // inFloatCnt, inFloat
    0, NULL,              // inStringCnt, inString
    0, NULL,              // inBufferSize, inBuffer
    NULL, NULL,              // outIntCnt, outInt
    &cnt, &pData,            // outFloatCnt, outFloat
    NULL, NULL,              // outStringCnt, outString
    NULL, NULL,              // outBufferSize, outBuffer
    simx_opmode_oneshot_wait);


  M[0][0] = pData[0];
  M[0][1] = pData[1];
  M[0][2] = pData[2];
  M[0][3] = pData[3];


  M[1][0] = pData[4];
  M[1][1] = pData[5];
  M[1][2] = pData[6];
  M[1][3] = pData[7];


  M[2][0] = pData[8];
  M[2][1] = pData[9];
  M[2][2] = pData[10];
  M[2][3] = pData[11];


  M[3][0] = 0;
  M[3][1] = 0;
  M[3][2] = 0;
  M[3][3] = 1;
}




// 读取当前机器人tip位置 Read Current Robot Tip Position
/
void CoppeliaRobot::readPosition(float currentPos[6])
{
  /*
  simxGetObjectPosition(clientID, ikTipHandle, robotHandle, __pos, simx_opmode_buffer);
  simxGetObjectOrientation(clientID, ikTipHandle, robotHandle, __rot, simx_opmode_buffer);
  currentPos[0] = __pos[0] * 1000; //mm
  currentPos[1] = __pos[1] * 1000; //mm
  currentPos[2] = __pos[2] * 1000; //mm
  currentPos[3] = __rot[0] * RAD_TO_DEG;
  currentPos[4] = __rot[1] * RAD_TO_DEG;
  currentPos[5] = __rot[2] * RAD_TO_DEG;
  */


  
  simxCallScriptFunction(
    clientID,
    scriptName.c_str(),            // the name of the associated obejct script
    sim_scripttype_childscript,      // the handle of the script
    "remoteApi_getPosition",            // Function name  脚本函数:获取tip位置 remoteApi_getPosition
    0, NULL,              // inIntCnt, inInt
    0, NULL,                // inFloatCnt, inFloat
    0, NULL,              // inStringCnt, inString
    0, NULL,              // inBufferSize, inBuffer
    NULL, NULL,              // outIntCnt, outInt
    &__cnt, &__position,        // outFloatCnt, outFloat
    NULL, NULL,              // outStringCnt, outString
    NULL, NULL,              // outBufferSize, outBuffer
    simx_opmode_buffer);
  //位姿数据  转换为合适单位
  if (__position != nullptr) {
    currentPos[0] = __position[0] * 1000; //mm
    currentPos[1] = __position[1] * 1000; //mm
    currentPos[2] = __position[2] * 1000; //mm
    currentPos[3] = __position[3] * RAD_TO_DEG;
    currentPos[4] = __position[4] * RAD_TO_DEG;
    currentPos[5] = __position[5] * RAD_TO_DEG;
  }
}
//读取对象位置
void CoppeliaRobot::readObjectPosition(string object_name, float currentPos[6]) {
  int object_handle;//对象句柄
  float position[3], orientation[3];//位置,姿态向量
  simxGetObjectHandle(clientID, object_name.c_str(), &object_handle, simx_opmode_oneshot_wait);//获取对象句柄
  simxGetObjectPosition(clientID, object_handle, robotHandle, position, simx_opmode_oneshot_wait);//获取对象位置
  simxGetObjectOrientation(clientID, object_handle, robotHandle, orientation, simx_opmode_oneshot_wait);//获取对象姿态
  currentPos[0] = position[0] * 1000;  //mm
  currentPos[1] = position[1] * 1000; //mm
  currentPos[2] = position[2] * 1000; //mm
  currentPos[3] = orientation[0] * RAD_TO_DEG;
  currentPos[4] = orientation[1] * RAD_TO_DEG;
  currentPos[5] = orientation[2] * RAD_TO_DEG;
}


// 直接设置机器人位置和方向(无速度控制) 需IK模式   Directly set the robot position and orientation (no speed control)
void CoppeliaRobot::setPosition2(float pos[6])
{
  float position[3], orientation[3];
  for (int i = 0; i < 3; i++) {
    position[i] = pos[i] / 1000;  // mm
    orientation[i] = pos[i + 3] * DEG_TO_RAD;
  }
  simxSetObjectPosition(clientID, ikTargetHandle, robotHandle, position, simx_opmode_oneshot_wait);//设置机器人位置
  simxSetObjectOrientation(clientID, ikTargetHandle, robotHandle, orientation, simx_opmode_oneshot_wait);//设置机器人方向
}


// 设置机器人速度Set Robot Speed : 0 - 100
///
void CoppeliaRobot::setSpeed(float vel, float ang_vel)
{
  float lin_vel = vel / 1000; //线速度
  float rad_vel = ang_vel * DEG_TO_RAD; //角速度


  float vel_data[2] = {lin_vel, rad_vel};//速度数组


  //调用脚本函数remoteApi_setSpeed
  int result = simxCallScriptFunction(
    clientID,
    scriptName.c_str(),            // the name of the associated obejct script
    sim_scripttype_childscript,      // the handle of the script
    "remoteApi_setSpeed",              // Function name
    0, NULL,              // inIntCnt, inInt
    2, vel_data,            // inFloatCnt, inFloat  2个速度,线速度和角速度
    0, NULL,              // inStringCnt, inString
    0, NULL,              // inBufferSize, inBuffer
    NULL, NULL,              // outIntCnt, outInt
    NULL, NULL,              // outFloatCnt, outFloat
    NULL, NULL,              // outStringCnt, outString
    NULL, NULL,              // outBufferSize, outBuffer
    simx_opmode_blocking);
}

三、主窗体程序:读取关节位置、tip位置。连接、断开服务器;启动、停止仿真。单关节控制、tip位置控制。

#include "MyForm.h"
#include "TeachingForm.h"
#include "include/coppeliasim.h"
#include "variables.h"
#include <iostream>
#include <windows.h>


using namespace System;
using namespace System::Windows::Forms;
using namespace UI_Demo;
using namespace std;


CoppeliaSim mSim; //仿真器对象
CoppeliaRobot mRobot;//机器人对象


float posData[6];//
int mode = 0;// 0-IK   1-FK
int step_index = 0;
float pos_step_data[6] = { 1, 5, 10, 20, 50, 100};//位置步进数据
float ang_step_data[6] = { 0.5, 1, 2, 5, 10, 20};//角度步进数据
float pos_step = 10;
float ang_step = 0;


// 函数声明Prototype Function
void thread_read_data(void*);


// 初始化对话框  Initialization program
void MyForm::on_init() {
  //设置定时器 Initialize timer:
  timer1->Interval = 50;
  timer1->Enabled = true;
  cb_selectmode->SelectedIndex = mode;


  _beginthread(thread_read_data, 0, NULL);//开启更新数据线程


  label_status->Text = "Initialize program";//初始化程序
}


// 更新变量posData数据 线程 Thread for updating the data
void thread_read_data(void*) {
  while (true) {
    if (mode == 0) {//ikmode
      mRobot.readPosition(posData);//读取tip位姿,得到posData[]
    }
    else {//关节模式
      mRobot.readCurrentJointPos(posData);//读取关节位置 得到posData[]
    }
    Sleep(50);
  }
}


//定时器函数:根据posData更新UI数据  Timer function: update the GUI information
void MyForm::on_timer() {
  update_pos_data();//定时更新UI位置数据 tb_pos_x->Text = posData[0].ToString("N3");


}
//连接  端口19997
void MyForm::btn_connect() {
  if (mSim.connect(19997)) {
    label_status->Text = "Coppeliasim connection success...";
    label_status->ForeColor = System::Drawing::Color::Green;
    mSim.startSimulation();
    mRobot.init("UR10");
  }
}
//开始仿真
void MyForm::btn_start_sim() {
  mSim.startSimulation();
}
//停止仿真
void MyForm::btn_stop_sim() {
  mSim.stopSimulation();
}
//修改标签
void MyForm::change_label() {
  mode = cb_selectmode->SelectedIndex;


  if (mode == 0) {//IK模式
    label_x->Text = "X:";
    label_y->Text = "Y:";
    label_z->Text = "Z:";
    label_rx->Text = "Rx:";
    label_ry->Text = "Ry:";
    label_rz->Text = "Rz:";


    btn_x_min->Text = "X-";
    btn_x_plus->Text = "X+";
    btn_y_min->Text = "Y-";
    btn_y_plus->Text = "Y+";
    btn_z_min->Text = "Z-";
    btn_z_plus->Text = "Z+";


    btn_rx_min->Text = "Rx-";
    btn_rx_plus->Text = "Rx+";
    btn_ry_min->Text = "Ry-";
    btn_ry_plus->Text = "Ry+";
    btn_rz_min->Text = "Rz-";
    btn_rz_plus->Text = "Rz+";
  }


  else {//关节模式
    label_x->Text = "J1:";
    label_y->Text = "J2:";
    label_z->Text = "J3:";
    label_rx->Text = "J4:";
    label_ry->Text = "J5:";
    label_rz->Text = "J6:";


    btn_x_min->Text = "J1-";
    btn_x_plus->Text = "J1+";
    btn_y_min->Text = "J2-";
    btn_y_plus->Text = "J2+";
    btn_z_min->Text = "J3-";
    btn_z_plus->Text = "J3+";


    btn_rx_min->Text = "J4-";
    btn_rx_plus->Text = "J4+";
    btn_ry_min->Text = "J5-";
    btn_ry_plus->Text = "J5+";
    btn_rz_min->Text = "J6-";
    btn_rz_plus->Text = "J6+";
  }


  update_set_data();
}


void MyForm::update_pos_data() {
  tb_pos_x->Text = posData[0].ToString("N3");
  tb_pos_y->Text = posData[1].ToString("N3");
  tb_pos_z->Text = posData[2].ToString("N3");
  tb_pos_rx->Text = posData[3].ToString("N3");
  tb_pos_ry->Text = posData[4].ToString("N3");
  tb_pos_rz->Text = posData[5].ToString("N3");
}
//更新数据
void MyForm::update_set_data() {
  float pos[6];
  if (mode == 0) {
    mRobot.readPosition(pos);//读取tip位姿
  }
  else {
    mRobot.readCurrentJointPos(pos);//读取关节位置
  }
  tb_set_x->Text = pos[0].ToString("N3");//保留3位小数
  tb_set_y->Text = pos[1].ToString("N3");
  tb_set_z->Text = pos[2].ToString("N3");
  tb_set_rx->Text = pos[3].ToString("N3");
  tb_set_ry->Text = pos[4].ToString("N3");
  tb_set_rz->Text = pos[5].ToString("N3");
}
//获取当前位置
void MyForm::btn_get_position() {
  tb_set_x->Text = tb_pos_x->Text;
  tb_set_y->Text = tb_pos_y->Text;
  tb_set_z->Text = tb_pos_z->Text;
  tb_set_rx->Text = tb_pos_rx->Text;
  tb_set_ry->Text = tb_pos_ry->Text;
  tb_set_rz->Text = tb_pos_rz->Text;
}
//设置机械臂位置
void MyForm::btn_set_position() {
  float cmdPos[6];
  cmdPos[0] = Convert::ToDouble(tb_set_x->Text);
  cmdPos[1] = Convert::ToDouble(tb_set_y->Text);
  cmdPos[2] = Convert::ToDouble(tb_set_z->Text);
  cmdPos[3] = Convert::ToDouble(tb_set_rx->Text);
  cmdPos[4] = Convert::ToDouble(tb_set_ry->Text);
  cmdPos[5] = Convert::ToDouble(tb_set_rz->Text);


  mRobot.setSpeed(30, 90);//设置速度:线速度、角速度


  if (mode == 0) {
    mRobot.setPosition(cmdPos, false);//设置tip位置
  }
  else {
    mRobot.setJointPosition(cmdPos, false);//设置关节位置
  }
}
//运动控制:单关节控制  或者 tip单维度控制
void MyForm::movement_control(int id) {
  if (mode == 0) {//IK模式
    float pos[6];
    mRobot.readPosition(pos);


    // x
    if (id == 1) pos[0] -= pos_step;
    else if (id == 2) pos[0] += pos_step;
    // y
    else if (id == 3) pos[1] -= pos_step;
    else if (id == 4) pos[1] += pos_step;
    // z
    else if (id == 5) pos[2] -= pos_step;
    else if (id == 6) pos[2] += pos_step;
    // w
    else if (id == 7) pos[3] -= ang_step;
    else if (id == 8) pos[3] += ang_step;
    // p
    else if (id == 9) pos[4] -= ang_step;
    else if (id == 10) pos[4] += ang_step;
    // r
    else if (id == 11) pos[5] -= ang_step;
    else if (id == 12) pos[5] += ang_step;


    mRobot.setPosition(pos, false);
  }
  else {//关节模式
    float pos[6];
    mRobot.readCurrentJointPos(pos);//读取当前关节位置


    // x
    if (id == 1) pos[0] -= ang_step;
    else if (id == 2) pos[0] += ang_step;
    // y
    else if (id == 3) pos[1] -= ang_step;
    else if (id == 4) pos[1] += ang_step;
    // z
    else if (id == 5) pos[2] -= ang_step;
    else if (id == 6) pos[2] += ang_step;
    // w
    else if (id == 7) pos[3] -= ang_step;
    else if (id == 8) pos[3] += ang_step;
    // p
    else if (id == 9) pos[4] -= ang_step;
    else if (id == 10) pos[4] += ang_step;
    // r
    else if (id == 11) pos[5] -= ang_step;
    else if (id == 12) pos[5] += ang_step;


    mRobot.setJointPosition(pos, false);
  }
}


//减小步进量
void MyForm::step_decrease() {
  char str[128];
  step_index--;
  if (step_index < 0) step_index = 0;
  pos_step = pos_step_data[step_index];
  ang_step = ang_step_data[step_index];
  sprintf(str,"Movement step = %.1f, %.1f", pos_step, ang_step);
  label_status->Text = gcnew String(str);
}
//增加步进量
void MyForm::step_increase() {
  char str[128];
  step_index++;
  if (step_index > 5) step_index = 5;//共6个步进模式
  pos_step = pos_step_data[step_index];
  ang_step = ang_step_data[step_index];
  sprintf(str,"Movement step = %.1f, %.1f", pos_step, ang_step);
  label_status->Text = gcnew String(str);
}
//显示示教窗口
void MyForm::show_teaching_form() {
  TeachingForm ^ form = gcnew TeachingForm;//实例化示教窗口
  form->Show();
}

四、示教窗口:指令(集合)操作

#include "TeachingForm.h"
#include "variables.h"  //外部数据定义
#include <msclr\marshal_cppstd.h>


using namespace System;
using namespace System::Windows::Forms;
using namespace UI_Demo;
using namespace std;
using namespace msclr::interop;


vector<record_t> recorded_pos;//指令集
//示教窗口初始化
void TeachingForm::on_init() {
  char str[256];
  record_t mPos;//一条指令数据
  int size = recorded_pos.size();//指令集数量
  //遍历所有指令
  for (int i = 0; i < size; i++) {
    mPos = recorded_pos[i];
    sprintf(str, "[%d] %s = %.3f, %.3f, %.3f, %.3f, %.3f, %.3f",
      mode, mPos.label.c_str(),
      mPos.pos[0],
      mPos.pos[1],
      mPos.pos[2],
      mPos.pos[3],
      mPos.pos[4],
      mPos.pos[5]
    );
    listBox1->Items->Add(gcnew String(str));//列表显示所有指令
  }


}




//添加指令
void TeachingForm::btn_add() {
  char str[256];
  record_t mPos;
  for(int i = 0; i < 6; i++) 
    mPos.pos[i] = posData[i];//当前位置数据


  mPos.label = marshal_as<string>(textBox1->Text);//标签 :用户输入
  
  if (mPos.label == "")
    mPos.label = "recorded_pos";//默认标签


  mPos.mode = mode;//指令模式
  sprintf(str, "[%d] %s = %.3f, %.3f, %.3f, %.3f, %.3f, %.3f", 
    mode, mPos.label.c_str(), 
    mPos.pos[0],
    mPos.pos[1],
    mPos.pos[2],
    mPos.pos[3],
    mPos.pos[4],
    mPos.pos[5]
    );//指令字符串
  printf(str);
  listBox1->Items->Add(gcnew String(str));//显示


  recorded_pos.push_back(mPos);//添加到指令集
}
//移除到选择的指令数据
void TeachingForm::btn_move() {
  record_t mPos;
  int index;
  
  mRobot.setSpeed(30, 30);//设置速度


  index = listBox1->SelectedIndex;//选择记录索引
  mPos = recorded_pos[index];//指令数据
  float cmdPos[6];
  for (int i = 0; i < 6; i++)
    cmdPos[i] = mPos.pos[i];//指令位置
  
  if (mPos.mode == 0)
    mRobot.setPosition(cmdPos, false);//移动tip位置
  else
    mRobot.setJointPosition(cmdPos, false);//移动关节位置
}


//删除
void TeachingForm::btn_delete() {


}

五、全局变量variables.h

#pragma once
#include <iostream>
#include <vector>
#include "include/coppeliasim.h"
//该类定义了全局变量
using namespace std;
//一条记录:指令记录
typedef struct record_t {
  int mode;//模式
  float pos[6];//位置
  string label;//标签
};


extern vector<record_t> recorded_pos;//指令集
extern float posData[6];//位置数组:tip位姿或者关节位置
extern int mode;//当前模式


extern CoppeliaSim mSim;//仿真器句柄
extern CoppeliaRobot mRobot;//机器人句柄

六、Lua脚本函数:C++可以调用

-- ======================================================
-- RemoteApi Functions
-- ======================================================
-- Set Robot Speed --
function remoteApi_setSpeed(inInt,inFloat,inString,inBuffe)
    local linear_vel=inFloat[1]
    local angular_vel=inFloat[2]
    local ikMaxVel={linear_vel, linear_vel, linear_vel, angular_vel}
    local fkMaxVel={angular_vel, angular_vel, angular_vel, angular_vel, angular_vel, angular_vel}
    print('Remote API -> Set robot speed = ', ikMaxVel)
    ik_data.maxVel = ikMaxVel   
    fk_data.maxVel = fkMaxVel 
end


-- Move Robot Position --
function remoteApi_movePosition(inInt,inFloat,inString,inBuffer)
    targetPos={}
    targetPos[1]=inFloat[1]
    targetPos[2]=inFloat[2]
    targetPos[3]=inFloat[3]
    targetPos[4]=inFloat[4]
    targetPos[5]=inFloat[5]
    targetPos[6]=inFloat[6]
    moveIkMode=true
end


-- Move Robot Joint Position --
function remoteApi_moveJointPosition(inInt,inFloat,inString,inBuffer)
    targetJoint={}
    for i=1,6,1 do
        targetJoint[i] = inFloat[i] 
    end
    moveJointMode=true
end


-- Get Object Position --
function remoteApi_getPosition()
    --val = sim.getFloatSignal('forceX')
    local pos=sim.getObjectPosition(simTip, simRobot)
    local rot=sim.getObjectOrientation(simTip, simRobot)
    local endpos = {pos[1],pos[2],pos[3],rot[1],rot[2],rot[3]}
    return {},endpos,{},''
end


-- Get Object Joint Position --
function remoteApi_getJointPosition()
    local jointPos={}
    for i=1,6,1 do
        jointPos[i]=sim.getJointPosition(simJoints[i])
    end
    return {},jointPos,{},''
end


-- Set Gripper --
function remoteApi_setGripper(state)
    velocity=0.11
    force=20
    if state[1]==0 then
        velocity=-velocity
    end
    local dat={}
    dat.velocity=velocity
    dat.force=force
    sim.writeCustomDataBlock(simGripper,'activity',sim.packTable(dat))
end




-- ========================================================
-- Kinematic Functions
-- ========================================================


-- Inverse Kinematic --
function moveToPoseCallback(q,velocity,accel,auxData)
    sim.setObjectPose(simTarget,-1,q)
    simIK.applyIkEnvironmentToScene(auxData.ikEnv,auxData.ikGroup)
end


function moveToPose_viaIK(auxData, pose)
    local pos = {pose[1], pose[2], pose[3]}
    local ori = {pose[4], pose[5], pose[6]}
    sim.setObjectPosition(simTargetPos, simRobot, pos)
    sim.setObjectOrientation(simTargetPos, simRobot, ori)
    local targetQ  = sim.getObjectPose(simTargetPos,-1)
    local currentQ = sim.getObjectPose(simTip,-1)
    return sim.moveToPose(-1,currentQ,auxData.maxVel,auxData.maxAccel,auxData.maxJerk,targetQ,moveToPoseCallback,auxData,nil)
end


-- Forward Kinematic --
function moveToConfigCallback(config,velocity,accel,auxData)
    for i=1,#auxData.joints,1 do
        local jh=auxData.joints[i]
        if sim.isDynamicallyEnabled(jh) then
            sim.setJointTargetPosition(jh,config[i])
        else    
            sim.setJointPosition(jh,config[i])
        end
    end
end


function moveToConfig_viaFK(auxData, goalConfig)
    local startConfig={}
    for i=1,#auxData.joints,1 do
        startConfig[i]=sim.getJointPosition(auxData.joints[i])
    end
    sim.moveToConfig(-1,startConfig,nil,nil,auxData.maxVel,auxData.maxAccel,auxData.maxJerk,goalConfig,nil,moveToConfigCallback,auxData,nil)
end

七、Lua脚本主函数

function coroutineMain()


    simJoints={}
    for i=1,6,1 do
        simJoints[i]=sim.getObject('./joint',{index=i-1})
    end
    
    -- FK movement data:
    local initConf={0,0,0,0,0,0}
    local vel=180
    local accel=40
    local jerk=80
    local maxVel={vel*math.pi/180,vel*math.pi/180,vel*math.pi/180,vel*math.pi/180,vel*math.pi/180,vel*math.pi/180}
    local maxAccel={accel*math.pi/180,accel*math.pi/180,accel*math.pi/180,accel*math.pi/180,accel*math.pi/180,accel*math.pi/180}
    local maxJerk={jerk*math.pi/180,jerk*math.pi/180,jerk*math.pi/180,jerk*math.pi/180,jerk*math.pi/180,jerk*math.pi/180}
    local initConf={}
    local maxConfVel={}
    local maxConfAccel={}
    local maxConfJerk={}
    for i=1,#simJoints,1 do
        initConf[i]=sim.getJointPosition(simJoints[i])
        maxConfVel[i]=3*math.pi/180
        maxConfAccel[i]=1.15
        maxConfJerk[i]=0.4
    end
    
    fk_data={}
    fk_data.maxVel=maxConfVel
    fk_data.maxAccel=maxConfAccel
    fk_data.maxJerk=maxConfJerk
    fk_data.joints=simJoints
    


    -- IK movement data:
    local ikMaxVel={0.45,0.45,0.45,4.5}
    local ikMaxAccel={0.8,0.8,0.8,0.9}
    local ikMaxJerk={0.6,0.6,0.6,0.8}
    
    ik_data={}
    ik_data.maxVel=ikMaxVel
    ik_data.maxAccel=ikMaxAccel
    ik_data.maxJerk=ikMaxJerk
    ik_data.ikEnv=ikEnv
    ik_data.ikGroup=ikGroup


    set_speed(50)


    -- Test IK Movement:
    --ik_command_demo()
    --fk_command_demo()
   
    --sim.wait(5)
    --sim.stopSimulation()
   
    
    while true do
        if moveIkMode then
            moveIkMode=false
            sim.setInt32Signal('moving_status',1)           -- Trigger for C++
            sim.setStringSignal('moving_signal', 'MOVING')  -- Trigger for Python
            moveToPose_viaIK(ik_data, targetPos)
            sim.setInt32Signal('moving_status',0)
            sim.setStringSignal('moving_signal', 'NOT_MOVING')
        end
        
        if moveJointMode then
            moveJointMode=false
            sim.setInt32Signal('moving_status',1)   
            sim.setStringSignal('moving_signal', 'MOVING')
            moveToConfig_viaFK(fk_data, targetJoint)
            sim.setInt32Signal('moving_status',0)
            sim.setStringSignal('moving_signal', 'NOT_MOVING')
        end
    end
end

参考:

https://marketplace.visualstudio.com/items?itemName=RichardKaiser.cppclrwinf


The End

评论 2
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值