导航

    蓝鲸ROS机器人论坛

    • 注册
    • 登录
    • 搜索
    • 版块
    • 话题
    • 热门
    1. 主页
    2. randoms
    ROS交流群
    ROS Group
    产品服务
    Product Service
    开源代码库
    Github
    官网
    Official website
    技术交流
    Technological exchanges
    激光雷达
    LIDAR
    ROS教程
    ROS Tourials
    深度学习
    Deep Learning
    机器视觉
    Computer Vision
    • 资料
    • 关注 0
    • 粉丝 1
    • 主题 5
    • 帖子 8
    • 最佳 0
    • 群组 1

    randoms

    @randoms

    administrators

    0
    声望
    1175
    资料浏览
    8
    帖子
    1
    粉丝
    0
    关注
    注册时间 最后登录
    电子邮件 randoms@randoms.com

    randoms 取消关注 关注
    administrators

    randoms 发布的最新帖子

    • 利用ros实时显示测试数据

      ros内部非常适合程序间进行通信,其内部又包含了非常方便的图标工具。下面就是一个用ros提供的工具做实时的舵机角度显示的例子。
      先看看效果吧

      0_1447227049969_Screenshot from 2015-11-11 15:30:37.png

      左侧是程序的log输出右侧是画出的角度图。

      程序的整体结构也是比较简单的。由手机端发送舵机控制指令到装有ros系统的电脑。电脑收到数据后,从数据中取出各个舵机的角度,同时创建一个叫做monitor的topic。然后把角度信息通过这个topic发送出去。rqt_plot监听这个topic就可以画出各个舵机的实时的角度图了。

      ok,开始写这个ros的package吧。

      首先,创建一个ros workspace

      cd ~/Documents
      mkdir -p ros/workspace/src
      cd ros/workspace/src
      catkin_init_workspace
      cd ..
      catkin_make
      source devel/setup.sh
      

      这时会发现目录结构如下图

      0_1447228312789_Screenshot from 2015-11-11 15:51:47.png

      接着创建一个ros package

      catkin_create_pkg statusmonitor std_msgs rospy roscpp
      roscd statusmonitor
      

      0_1447228924693_Screenshot from 2015-11-11 16:01:58.png

      现在的目录结构应该如上图所示

      src文件夹内创建monitor.py内容如下

      #!/usr/bin/env python
      # license removed for brevity
      import rospy
      import socket
      from statusmonitor.msg import *
      import cmds as Commands
      import threading
      
      PACKAGE_HEADER = [205, 235, 215]
      dataCache = []
      
      def getDataFromReq(req):
          pass
      
      def unpackReq(req):
          global dataCache
          res = []
          packageList = splitReq(req)
          # process the first package
          completeData = dataCache + packageList[0]
          packageList.remove(packageList[0])
          packageList =  splitReq(completeData) + packageList
      
          for count in range(0, len(packageList)):
              if len(packageList[count]) != 0 and len(packageList[count]) == packageList[count][0] + 1:
                  res.append(packageList[count][1:])
          lastOne = packageList[-1:][0] # the last one
          if len(lastOne) == 0 or len(lastOne) != lastOne[0] + 1:
              dataCache = lastOne
          return res
      
      
      def findPackageHeader(req):
          if len(req) < 3:
              return -1
          for count in range(0, len(req) - 2):
              if req[count] == PACKAGE_HEADER[0] and req[count + 1] == PACKAGE_HEADER[1] and req[count + 2] == PACKAGE_HEADER[2]:
                  return count
          return -1
      
      def splitReq(req):
          res = []
          startIndex = 0
          newIndex = 0
          while True:
              newIndex = findPackageHeader(req[startIndex:])
              if newIndex == -1:
                  break
              res.append(req[startIndex: startIndex + newIndex])
              startIndex = newIndex + 3 + startIndex
          res.append(req[startIndex:])
          return res
      
      def parseData(cmds):
          res = None
          for count in range(0, len(cmds)):
              if chr(cmds[count][0]) == Commands.CMD_STEER_SET:
                  if cmds[count][1] == 1:
                      res = Steer1()
                      res.angle = cmds[count][2] * 0xff + cmds[count][3]
                      pub1.publish(res)
                  if cmds[count][1] == 2:
                      res = steer2()
                      res.angle = cmds[count][2] * 0xff + cmds[count][3]
                      pub2.publish(res)
                  if cmds[count][1] == 3:
                      res = steer3()
                      res.angle = cmds[count][2] * 0xff + cmds[count][3]
                      pub3.publish(res)
                  if cmds[count][1] == 4:
                      res = steer4()
                      res.angle = cmds[count][2] * 0xff + cmds[count][3]
                      pub4.publish(res)
                  if cmds[count][1] == 5:
                      res = steer5()
                      res.angle = cmds[count][2] * 0xff + cmds[count][3]
                      pub5.publish(res)
                  if cmds[count][1] == 6:
                      res = steer6()
                      res.angle = cmds[count][2] * 0xff + cmds[count][3]
                      pub6.publish(res)
                  if cmds[count][1] == 7:
                      res = steer7()
                      res.angle = cmds[count][2] * 0xff + cmds[count][3]
                      pub7.publish(res)
                  if cmds[count][1] == 8:
                      res = steer8()
                      res.angle = cmds[count][2] * 0xff + cmds[count][3]
                      pub8.publish(res)
                  if cmds[count][1] == 9:
                      res = steer9()
                      res.angle = cmds[count][2] * 0xff + cmds[count][3]
                      pub9.publish(res)
                  if cmds[count][1] == 10:
                      res = steer10()
                      res.angle = cmds[count][2] * 0xff + cmds[count][3]
                      pub10.publish(res)
                  if cmds[count][1] == 11:
                      res = steer11()
                      res.angle = cmds[count][2] * 0xff + cmds[count][3]
                      pub11.publish(res)
                  if cmds[count][1] == 12:
                      res = steer12()
                      res.angle = cmds[count][2] * 0xff + cmds[count][3]
                      pub12.publish(res)
                  if cmds[count][1] == 13:
                      res = steer13()
                      res.angle = cmds[count][2] * 0xff + cmds[count][3]
                      pub13.publish(res)
                  if cmds[count][1] == 14:
                      res = steer14()
                      res.angle = cmds[count][2] * 0xff + cmds[count][3]
                      pub14.publish(res)
          return res
      
      class handleSocket(threading.Thread):
      
          def __init__(self, conn, addr):
              threading.Thread.__init__(self)
              self.conn = conn
              self.addr = addr
      
          def run(self):
              print 'Connection address:', addr
              while 1:
                  data = conn.recv(BUFFER_SIZE)
                  if not data: break
                  conn.send(data)  # echo
                  rospy.loginfo(data)
                  dataList = []
                  for c in data:
                      dataList.append(ord(c))
                  parseData(unpackReq(dataList))
      
              conn.close()
      
      
      
      
      if __name__ == '__main__':
      
          pub1 = rospy.Publisher('monitor_steer1', Steer1, queue_size=10)
          pub2 = rospy.Publisher('monitor_steer2', steer2, queue_size=10)
          pub3 = rospy.Publisher('monitor_steer3', steer3, queue_size=10)
          pub4 = rospy.Publisher('monitor_steer4', steer4, queue_size=10)
          pub5 = rospy.Publisher('monitor_steer5', steer5, queue_size=10)
          pub6 = rospy.Publisher('monitor_steer6', steer6, queue_size=10)
          pub7 = rospy.Publisher('monitor_steer7', steer7, queue_size=10)
          pub8 = rospy.Publisher('monitor_steer8', steer8, queue_size=10)
          pub9 = rospy.Publisher('monitor_steer9', steer9, queue_size=10)
          pub10 = rospy.Publisher('monitor_steer10', steer10, queue_size=10)
          pub11 = rospy.Publisher('monitor_steer11', steer11, queue_size=10)
          pub12 = rospy.Publisher('monitor_steer12', steer12, queue_size=10)
          pub13 = rospy.Publisher('monitor_steer13', steer13, queue_size=10)
          pub14 = rospy.Publisher('monitor_steer14', steer14, queue_size=10)
      
          rospy.init_node('talker', anonymous=True)
      
      
          TCP_IP = '0.0.0.0'
          TCP_PORT = 50000
          BUFFER_SIZE = 1024  # Normally 1024, but we want fast response
      
      
          s = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
          s.bind((TCP_IP, TCP_PORT))
          s.listen(1)
          while 1:
              conn, addr = s.accept()
              handleSocket(conn, addr).start()
      

      从程序入口开始说明。首先创建了一系列的ros的publisher,这个可以用来向topic发送信息。然后初始化ros节点。
      接着创建一个socket,监听发送由机器人控制端发送来的指令数据。收到数据后就把数据包解开,提取处各个舵机的角度,通过最开始创建的publisher发送出去。

      主程序就是这样,下面开始创建ros message。在src文件夹内创建msg文件夹,并在其中创建Steer1.msg到Steer14.msg,这些文件的内容都是一样的

      float32 angle
      
      float32 res
      

      msg文件就是表明msg的格式的文件。之后编译包的时候这些文件会被编译成c++文件和python文件。
      接着就是修改makefile,因为msg是需要编译的嘛。

      find_package(catkin REQUIRED COMPONENTS
        roscpp
        rospy
        std_msgs
        message_generation
      )
      

      第一步就是在find_package中添加message_generation
      然后添加msg文件

      add_message_files(
         FILES
         Steer1.msg
         Steer2.msg
         Steer3.msg
         Steer4.msg
         Steer5.msg
         Steer6.msg
         Steer7.msg
         Steer8.msg
         Steer9.msg
         Steer10.msg
         Steer11.msg
         Steer12.msg
         Steer13.msg
        )
      

      在generate msg 添加 std_msg

      generate_messages(
         DEPENDENCIES
        std_msgs
      )
      

      在依赖中加入message_runtime

      catkin_package(
      # INCLUDE_DIRS include
      LIBRARIES statusmonitor
      CATKIN_DEPENDS roscpp rospy std_msgs message_runtime
      #  DEPENDS system_lib
      )
      

      到这里就应该差不多了。

      开始编译

      cd ~/Documents
      cd ros/workspace/src
      catkin_make
      

      如果输出如下图就说明编译正确
      0_1447377293843_Screenshot from 2015-11-13 09:14:46.png

      下一步就是开始运行了

      source devel/setup.sh
      rosrun statusmonitor monitor.py
      

      这样当收到控制端发送来的数据时就会如下显示

      0_1447377469742_Screenshot from 2015-11-13 09:17:36.png

      在一个新终端中启动rqt_plot,然后选择想要观察的topic就行了

      0_1447377619619_Screenshot from 2015-11-13 09:20:09.png

      发布在 技术交流
      randoms
      randoms
    • 公司代码托管系统使用简介

      公司的代码托管系统是利用基于git的网页工具gitlab。Gitlab和Github很类似。基本上可以算是自己架设的一个Github网站。

      什么是Git?

      简单来说就是一个版本管理系统。和其他代码管理有些不同的是它的重点放在了分支的管理上。这样更利于协同开发。更详细的信息可以看这里。

      具体使用

      Git的指令比较多,各种参数也比较难记。我推荐使用图形化的客户端来具体操作。比如source tree。下面就基于Source Tree介绍一下具体的代码如何管理。

      注册Gitlab账号

      打开登陆页面,如下图所示
      0_1446425391043_QQ截图20151102084938.png
      和一般的网站注册一样,注册一个Gitlab账号。

      注册,验证邮箱,登陆网站之后就可以看到Gitlab的主页面了。
      0_1446425679699_QQ截图20151102085349.png

      创建Gitlab项目

      选择 New Project就可以创建项目了。输入项目相关的信息点击 CREATE PROJECT项目就创建完了。

      0_1446425815395_QQ截图20151102085645.png

      如果你不想公开这个项目那么你可以选择 Private。这样只有你指定的人才能访问这个项目。

      Clone这个项目

      项目创建完成之后,进入到新创建的项目的主页可以看到下图的界面。
      0_1446425956684_QQ截图20151102085832.png
      先点击 HTTP 按钮,然后复制文本框中的项目地址(目前只有http模式测试过,ssh还没测试过,可能会有问题)。

      打开Source Tree
      点击最上面菜单中的 文件 -> 克隆/新建

      0_1446426254752_QQ截图20151102090237.png

      在源路径中粘贴刚才复制的那个地址。填完其他相关内容后选择克隆就能把项目复制到本地了。

      提交和推送代码

      把项目文件添加到项目文件夹内后

      0_1446426546478_QQ截图20151102090802.png
      选择你要提交的代码,点击左侧的单选框,文件就会被暂存起来。

      0_1446426718707_QQ截图20151102091146.png

      选择完成之后点击最上面的提交,就可以把代码提交到本地了。如果想要把更改推送到服务器就点击最上面的推送按钮。

      0_1446426837180_QQ截图20151102091348.png

      这样就可以在服务器上看到你的项目文件了。

      其他

      暂时还没想到,以后再添加。

      发布在 技术交流
      randoms
      randoms
    • 我们的Git服务器开通了

      我们的Git服务器开通了!现在你可以把代码托管到这里了。

      发布在 最新公告
      randoms
      randoms
    • RE: 这个论坛是谁搭建的啊?

      @choury 还行吧

      发布在 讨论区
      randoms
      randoms
    • RE: 这个论坛是谁搭建的啊?

      我知道了,我的流量被你监控了:(

      发布在 讨论区
      randoms
      randoms
    • RE: 这个论坛是谁搭建的啊?

      你怎么知道这个论坛的?才建好谁都没告诉呢。
      这个是我建的。用的NodeBB。字数限制应该是它自己带的。

      发布在 讨论区
      randoms
      randoms
    • 电机控制与缓动函数

      问题

      在机器人的控制中最最基本的就是电机的控制。以舵机为例,最简单的控制方法就是直接给想要控制的舵机发送目标角度。但是我们实际会发现这样会有很多问题。比如舵机的动作速度没办法控制。动作看起来非常的生硬,直来直去。这样的控制也会比较影响舵机的使用寿命。这样就会出现一个问题,如何能够流畅的控制电机呢?

      首先什么样的动作才叫做流畅呢?


      同样是左右来回运动的两个方块,第二块的运动方式就要比第一块流畅许多。第一块只是一恒定大小的速度在运动,在两个边缘处的速度是突变的。这样对电机的伤害就很大。第二块的运动包含了加速和减速的过程,整过过程总电机的力相对要更均匀些。

      如何选取缓动函数

      现在我们已经知道了应该在运动中加入适当的过渡变化。那么如何选取合适的过度函数呢?
      这里实际上可以考虑成一个常见的物理运动过程。比如一个有阻尼的弹簧振子的运动。

      0_1446100359847_Damped_spring.gif

      根据阻尼大小的不同可以分为欠阻尼,过阻尼和临界阻尼三种状态。这些状态都运动特点如下图所示

      0_1446100484976_Damping_types.PNG

      假如我们想要把一个运动的电机停下来。按照阻尼运动来进行控制就是一个比较好的方式。但是在实际开发过程中,我们肯定不能直接使用上图的这种运动方程,因为算起来会比较复杂。在计算机绘图程序中经常使用贝塞尔函数来绘制平滑的曲线。利用这个函数就可以近似的模拟出以上的几个运动方程。

      比如欠阻尼的情况
      0_1446100961675_QQ截图20151029144214.png
      又比如过阻尼的情况
      0_1446101025205_QQ截图20151029144335.png

      具体怎么实现呢

      这个具体的实现过程和一般程序的动画控制函数差不多。下面以java为例来分析具体应该如何实现。
      一半的动画函数都包含以下几个参数,初始值, 结束值,时间函数(这个就是用来控制变化曲线的),更新函数。下面是我的code

      public static ActionStatusController actionAnimation(final int start, final int end, final int duration, final AnimationTimeFunction timeFunction, final AnimationHandler controlFunction){
          final ThreadUtils mAnimationThread = new ThreadUtils(new OnThreadStartHandler(){
              @Override
              public void OnStart() {
                  super.OnStart();
                  int changes = end - start;
                  int time = 0;
                  while (time < duration){
                      controlFunction.onProgress((int)(start + changes * timeFunction.getInterpolation((float)time/duration)));
                      try{
                          Thread.sleep(40);
                          time += 40;
                      }catch (Exception e){
                          e.printStackTrace();
                          break; //action was canceled
                      }
                  }
              }
          });
          ActionStatusController mController = new ActionStatusController(mAnimationThread);
          return mController;
      }
      

      每次根据时间算出变化量,然后再把变化量传入到更新函数里面去进行具体的操作。
      因为一个动作可能包含了一些列电机的很多行为,所以为了使用方便可以包装出一个动作控制类。

      package com.novelor.servicebot.servicebot.models;
      
      import android.util.Log;
      
      import com.novelor.servicebot.servicebot.callbacks.OnThreadStartHandler;
      import com.novelor.servicebot.servicebot.utils.ArrayUtils;
      import com.novelor.servicebot.servicebot.utils.ThreadUtils;
      
      import java.util.Collection;
      
      /**
       * Created by randoms on 2015/10/23.
       */
      public class ActionStatusController {
      
          private ThreadUtils mAction;
          private boolean startFlag = false;
      
          public boolean isFinished(){
              return !mAction.isAlive();
          }
      
          public ActionStatusController (ThreadUtils mAction){
              this.mAction = mAction;
          }
      
          public void start(){
      
              startFlag = true;
              mAction.start();
          }
      
          public void cancel(){
              this.mAction.interrupt();
          }
      
          public ActionStatusController then(ActionStatusController next){
              while (!isFinished() || !startFlag){
                  try{
                      Thread.sleep(5);
                  }catch (Exception e){e.printStackTrace();}
              }
              next.start();
          return next;
      }
      
      public ActionStatusController then(ActionStatusController[] nexts){
          Log.d("Bot", "here1");
          while (!isFinished() || !startFlag){
              try{
                  Thread.sleep(5);
              }catch (Exception e){e.printStackTrace();}
          }
          Log.d("Bot", "here2");
          for(int i = 0;i<nexts.length;i++){
              nexts[i].start();
          }
          // wait all actions to finish
          for(int i=0;i<nexts.length;i++){
              while (!nexts[i].isFinished() || !nexts[i].startFlag){
                  try{
                      Thread.sleep(5);
                  }catch (Exception e){e.printStackTrace();}
              }
          }
          ActionStatusController res =  new ActionStatusController(new ThreadUtils(new OnThreadStartHandler(){
              @Override
              public void OnStart() {
                  super.OnStart();
              }
          }));
          res.start();
          return res;
      }
      
      public static ActionStatusController Start(ActionStatusController[] actions){
              Log.d("Bot", "before start");
              for(int i = 0;i<actions.length;i++){
                  actions[i].start();
              }
              Log.d("Bot", "started");
              for(int i=0;i<actions.length;i++){
                  while (!actions[i].isFinished() || !actions[i].startFlag){
                      try{
                          Thread.sleep(5);
                      }catch (Exception e){e.printStackTrace();}
                  }
              }
              ActionStatusController res =  new ActionStatusController(new ThreadUtils(new OnThreadStartHandler(){
                  @Override
                  public void OnStart() {
                      super.OnStart();
                  }
              }));
              res.start();
              return res;
          }
      }
      

      这样在实际使用中就可以这样了

      ActionStatusController.Start(reset()).then(new ActionStatusController[]{
                          AnimateSteer(BotApi.STEER_ANGEL_CURRENT, 194, 500, 1),
                          AnimateSteer(BotApi.STEER_ANGEL_CURRENT, 180, 500, 2),
                          AnimateSteer(BotApi.STEER_ANGEL_CURRENT, 180, 500, 3),
                          AnimateSteer(BotApi.STEER_ANGEL_CURRENT, 158, 500, 4),
                          AnimateSteer(BotApi.STEER_ANGEL_CURRENT, 25, 500, 5),
                          AnimateSteer(BotApi.STEER_ANGEL_CURRENT, 3, 500, BotApi.STEER_RIGHT_HAND)
                  }).then(new ActionStatusController[]{
                          AnimateSteer(BotApi.STEER_ANGEL_CURRENT, 194, 500, 1),
                          AnimateSteer(BotApi.STEER_ANGEL_CURRENT, 140, 500, 2),
                          AnimateSteer(BotApi.STEER_ANGEL_CURRENT, 172, 500, 3),
                          AnimateSteer(BotApi.STEER_ANGEL_CURRENT, 500, 3, BotApi.STEER_RIGHT_HAND),
                  }).then(
                          AnimateSteer(BotApi.STEER_ANGEL_CURRENT, 39, 300, BotApi.STEER_RIGHT_HAND) // 抓
                  ).then(
                          AnimateSteer(BotApi.STEER_ANGEL_CURRENT, 165, 300, 3)
                  ).then(new ActionStatusController[]{
                          AnimateSteer(BotApi.STEER_ANGEL_CURRENT, 237, 500, 1),
                          AnimateSteer(BotApi.STEER_ANGEL_CURRENT, 144, 500, 3),
                          AnimateSteer(BotApi.STEER_ANGEL_CURRENT, 0, 500, 5)
                  }).then(
                          AnimateSteer(BotApi.STEER_ANGEL_CURRENT, 12, 300, BotApi.STEER_RIGHT_HAND)
                  ).then(
                          AnimateSteer(BotApi.STEER_ANGEL_CURRENT, 172, 300, 2)
                  ).then(
                          AnimateSteer(BotApi.STEER_ANGEL_CURRENT, 93, 300, 5)
                  ).then(
                          reset()
                  )
      
      /**
       *
       * @param start
       * @param end
       * @param duration
       * @param index index start from 1
       * @return
       */
      public static ActionStatusController AnimateSteer(int start, int end, int duration, final int index){
          if(start == BotApi.STEER_ANGEL_DEFAULT){
              start = BotApi.getDefaultAngles()[BotApi.jointMapping[index -1] - 1];
          }
          if(start == BotApi.STEER_ANGEL_CURRENT){
              start = BotApi.getCurrentAngles()[BotApi.jointMapping[index -1] - 1];
          }
          if(end == BotApi.STEER_ANGEL_DEFAULT){
              end = BotApi.getDefaultAngles()[BotApi.jointMapping[index -1] - 1];
          }
          if(end == BotApi.STEER_ANGEL_CURRENT){
              end = BotApi.getCurrentAngles()[BotApi.jointMapping[index -1] - 1];
          }
          return actionAnimation(start, end, duration, new Cubicbezier(0.445, 0.05, 0.55, 0.95), new AnimationHandler(){
              @Override
              public void onProgress(int value) {
                  super.onProgress(value);
                  BotApi.SetSteer(BotApi.jointMapping[index - 1], value);
              }
          });
      }
      

      其中Cubicbezier(0.445, 0.05, 0.55, 0.95)就是缓动函数

      package com.novelor.servicebot.servicebot.utils;
      
      import android.graphics.PointF;
      
      import com.novelor.servicebot.servicebot.models.AnimationTimeFunction;
      
      /**
       * Created by randoms on 2015/10/23.
       */
      public class Cubicbezier implements AnimationTimeFunction {
      
          protected PointF start;
          protected PointF end;
          protected PointF a = new PointF();
          protected PointF b = new PointF();
          protected PointF c = new PointF();
      
          public Cubicbezier(PointF start, PointF end) throws IllegalArgumentException {
              if (start.x < 0 || start.x > 1) {
                  throw new IllegalArgumentException("startX value must be in the range [0, 1]");
              }
              if (end.x < 0 || end.x > 1) {
                  throw new IllegalArgumentException("endX value must be in the range [0, 1]");
              }
              this.start = start;
              this.end = end;
          }
      
          public Cubicbezier(float startX, float startY, float endX, float endY) {
              this(new PointF(startX, startY), new PointF(endX, endY));
          }
      
          public Cubicbezier(double startX, double startY, double endX, double endY) {
              this((float) startX, (float) startY, (float) endX, (float) endY);
          }
      
          /**
           *
           * @param time between 0 and 1
           * @return between 0 and 1
           */
          @Override
          public float getInterpolation(float time) {
              return getBezierCoordinateY(getXForTime(time));
          }
      
          protected float getBezierCoordinateY(float time) {
              c.y = 3 * start.y;
              b.y = 3 * (end.y - start.y) - c.y;
              a.y = 1 - c.y - b.y;
              return time * (c.y + time * (b.y + time * a.y));
          }
      
          protected float getXForTime(float time) {
              float x = time;
              float z;
              for (int i = 1; i < 14; i++) {
                  z = getBezierCoordinateX(x) - time;
              if (Math.abs(z) < 1e-3) {
                  break;
              }
              x -= z / getXDerivate(x);
          }
          return x;
      }
      
      private float getXDerivate(float t) {
          return c.x + t * (2 * b.x + 3 * a.x * t);
      }
      
      private float getBezierCoordinateX(float time) {
          c.x = 3 * start.x;
          b.x = 3 * (end.x - start.x) - c.x;
          a.x = 1 - c.x - b.x;
          return time * (c.x + time * (b.x + time * a.x));
      }
      }
      

      暂搁于此,以后再优化补充。

      发布在 技术交流
      randoms
      randoms
    • Welcome to your NodeBB!

      Welcome to your brand new NodeBB forum!

      This is what a topic and post looks like. As an administator, you can edit the post’s title and content.
      To customise your forum, go to the Administrator Control Panel. You can modify all aspects of your forum there, including installation of third-party plugins.

      Additional Resources

      • NodeBB Documentation
      • Community Support Forum
      • Project repository
      发布在 讨论区
      randoms
      randoms