ROS連接ABB機(jī)械臂調(diào)試詳細(xì)教程-ROS(indigo)和ABB RobotStudio 6.03.02-

      網(wǎng)友投稿 1172 2022-05-30

      在ROS industrial介紹中,給出了ROS和常用機(jī)械臂的連接方式。具體信息可以參考:http://wiki.ros.org/Industrial

      ROS連接ABB機(jī)械臂調(diào)試詳細(xì)教程-ROS(indigo)和ABB RobotStudio 6.03.02-

      補(bǔ)充:https://github.com/robotics/open_abb

      open-abb-driver

      Control ABB robots remotely with ROS, Python, or C++

      What is it?

      open-abb-driver consists of two main parts. The first is a program which is written in the ABB robot control language, RAPID, which allows remote clients to send requests for actions (such as joint moves, cartesian moves, speed changes, etc.). The second is a series of libraries to interact with the robot from remote computers, using several different control schemes. You can use the ROS driver, which allows control using ROS services and publishers. You can also include the Python or C++ libraries to communicate with the robot directly (both located in abb_node/packages/abb_comm), and bypass ROS completely.

      Requirements

      ABB IRC5 controller

      6 DOF robotic manipulator

      Robot must have the following factory software options

      "PC Interface"

      "Multitasking" (required for position feedback stream)

      Quick Start

      Robot Setup

      Install the RAPID module 'SERVER'

      Using RobotStudio online mode is the easiest way to do this, check out the wiki article for details.

      For position feedback, install the RAPID module 'LOGGER' into another task.

      In SERVER.mod, check to make sure the "ipController" specified is the same as your robot. The default robot IP is 192.168.125.1

      Start the programs on the robot

      Production Window->PP to Main, then press the play button.

      Computer Setup

      Verify that your computer is on the same subnet as the robot.

      Try pinging the robot (default IP is 192.168.125.1).

      Before trying ROS, it's pretty easy to check functionality using the simple python interface.

      Note that you must either copy abb_node/packages/abb_comm/abb.py to your local directory or somewhere included in your PYTHONPATH environment.

      To set up the ROS node (Fuerte only at the moment), copy abb_node to somewhere in your $ROS_PACKAGE_PATH.

      If you did that correctly, try:

      roscd abb_node

      rosmake abb_node

      roslaunch abb_node abb_tf.launch

      調(diào)試視頻鏈接:http://v.youku.com/v_show/id_XMTc0MzUxNDU4OA

      ROS官網(wǎng)給出了一些示例,可以移植應(yīng)用(120 120t 4400 2400 5400 6600 6640),參考網(wǎng)址:

      1 http://wiki.ros.org/abb

      2 https://github.com/ros-industrial/abb

      3 https://github.com/ros-industrial/abb_experimental

      下面詳細(xì)介紹,如何用ROS中MoveIt!規(guī)劃并控制ABB RobotStudio中機(jī)械臂的運(yùn)動(dòng)。

      MoveIt!:http://moveit.ros.org/

      ABB RobotStudio:http://blog.csdn.net/ZhangRelay/article/details/51177098

      ----官方教程分為3個(gè)小節(jié)----

      The following tutorials are provided to demonstrate installation and operation of an?ABB?robot using the ROS Industrial interfaces:

      Installing the ABB ROS Server

      This tutorial walks through the steps of installing the ROS server code on the ABB robot controller and configuring the required controller settings.

      Running the ROS Server

      This tutorial describes how to run the ABB ROS Server, so the robot will execute motion commands sent from the ROS client node.

      The following tutorials show how to use the ABB Robot Studio with the driver:

      Using Simulated Robot in Robot Studio

      This tutorial describes how to setup the ABB RobotStudio simulator for use with the ROS-Industrial driver.

      分別為:安裝ABB ROS服務(wù)器,運(yùn)行ROS 服務(wù)器和在RobotStudio中使用仿真機(jī)器人,這里以仿真機(jī)器人為例,

      當(dāng)然配置完成后就可以控制真實(shí)機(jī)械臂運(yùn)動(dòng)了。

      A 在RobotStudio中使用仿真機(jī)器人

      通過(guò)使用仿真機(jī)械臂替代真實(shí)機(jī)械臂,可以在ROS和ABB機(jī)械臂進(jìn)行通信仿真。這種情況下,通常有兩臺(tái)PC,

      一臺(tái)運(yùn)行windows及ABB機(jī)械臂,winpc;另一臺(tái)運(yùn)行ubuntu和ROS,rospc。

      1 需要熟悉ABB RobotStudio使用

      1.1 新建一個(gè)空工作站解決方案:

      1.2 在ABB模型庫(kù)中選擇一款機(jī)械臂,這里以IRB120_3_58__01為例:

      1.3 選擇機(jī)器人系統(tǒng),點(diǎn)擊從布局:

      1.4 點(diǎn)擊下一步,出現(xiàn)下面界面,點(diǎn)擊選項(xiàng):

      1.5 通過(guò)過(guò)濾器快速添加616-1 PC interface 和 623-1 Multitasking后,點(diǎn)擊完成:

      2?安裝RAPID文件

      2.1 到創(chuàng)建的文檔\RobotStudio\Systems下選擇對(duì)應(yīng)的工作站

      2.2 打開,新建ROS文件夾,并復(fù)制\abb_driver\rapid到其中(-https://github.com/ros-industrial/abb):

      2.3 查看目前winpc的IP地址,并寫入到ROS_socket.sys中對(duì)應(yīng)處,如下:

      3?選擇控制器,配置示教器:

      在配置中,為了使用方便先將語(yǔ)言設(shè)置為中文:

      配置到手動(dòng)模式,就可以進(jìn)行下一步,安裝ROS服務(wù)器。

      B 安裝ROS服務(wù)器

      必須具備的組件清單:

      Multitasking (623-1) -- for parallel socket communications

      Socket Messaging (672-1) -- for communications with a ROS PC

      for recent RobotWare versions, this option is included with "PC Interface (616-1)"

      RobotWare OS >= 5.13 -- for required socket options

      earlier versions may work, but will require modifications to the RAPID code

      如果不全,仿真沒有問題,但無(wú)法控制實(shí)際機(jī)器人。

      之前,已經(jīng)將代碼文件復(fù)制到相應(yīng)文件夾下了,如(e.g. //HOME/ROS/*)。

      進(jìn)行下一步操作。

      1 配置控制器

      這里文件說(shuō)明如下:

      Shared by all tasks

      ROS_common.sys -- Global variables and data types shared by all files

      ROS_socket.sys -- Socket handling and simple_message implementation

      ROS_messages.sys -- Implementation of specific message types

      Specific task modules

      ROS_stateServer.mod -- Broadcast joint position and state data

      ROS_motionServer.mod -- Receive robot motion commands

      ROS_motion.mod -- Issues motion commands to the robot

      1.1 創(chuàng)建任務(wù)

      在ABB--控制器--配置編輯器--Controller--Task:

      Create 3 tasks as follows:

      Name

      Type

      Trust Level

      ROS連接ABB機(jī)械臂調(diào)試詳細(xì)教程-ROS(indigo)和ABB RobotStudio 6.03.02-

      Entry

      Motion Task

      ROS_StateServer

      SEMISTATIC

      NoSafety

      main

      NO

      ROS_MotionServer

      SEMISTATIC

      SysStop

      main

      NO

      T_ROB1

      NORMAL

      main

      YES

      It is easiest to wait until all configuration tasks are completed before rebooting the controller.

      NOTES:

      The T_ROB1 motion task probably already exists on your controller.

      If T_ROB1 has existing motion-control modules, you may need to rename the main() routine in ROS_Motion.mod to ROS_main(). In this case, set the Entry point for T_ROB1 task to ROS_main().

      For multi-robot controllers, specify the desired robot (e.g.?rob1) for each task

      SEMISTATIC tasks will auto-start when controller is booted. They are visible, but cannot be easily seen for troubleshooting. For debug or development purposes, it may be desired to set both ROS_*Server tasks to Type=NORMAL.

      1.2 加載模塊到任務(wù)

      在ABB--控制器--配置編輯器--Controller--Automatic Loading of Modules:

      File

      Task

      Installed

      All Tasks

      Hidden

      HOME:/ROS/ROS_common.sys

      NO

      YES

      NO

      HOME:/ROS/ROS_socket.sys

      NO

      YES

      NO

      HOME:/ROS/ROS_messages.sys

      NO

      YES

      NO

      HOME:/ROS/ROS_stateServer.mod

      ROS_StateServer

      NO

      NO

      NO

      HOME:/ROS/ROS_motionServer.mod

      ROS_MotionServer

      NO

      NO

      NO

      HOME:/ROS/ROS_motion.mod

      T_ROB1

      NO

      NO

      NO

      添加完成后如下所示:

      然后,重啟控制器,應(yīng)用更改。

      1.3 更新

      在控制器--重啟中選擇合適模式進(jìn)行重啟,完成后可以看到如下:

      如果IP錯(cuò)誤:

      設(shè)置正確IP后,顯示:

      補(bǔ)充RAPID:

      ROS_motionServer:

      MODULE ROS_motionServer ! Software License Agreement (BSD License) ! ! Copyright (c) 2012, Edward Venator, Case Western Reserve University ! Copyright (c) 2012, Jeremy Zoss, Southwest Research Institute ! All rights reserved. ! ! Redistribution and use in source and binary forms, with or without modification, ! are permitted provided that the following conditions are met: ! ! Redistributions of source code must retain the above copyright notice, this ! list of conditions and the following disclaimer. ! Redistributions in binary form must reproduce the above copyright notice, this ! list of conditions and the following disclaimer in the documentation ! and/or other materials provided with the distribution. ! Neither the name of the Case Western Reserve University nor the names of its contributors ! may be used to endorse or promote products derived from this software without ! specific prior written permission. ! ! THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY ! EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES ! OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT ! SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, ! INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED ! TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR ! BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN ! CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY ! WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. LOCAL CONST num server_port := 11000; LOCAL VAR socketdev server_socket; LOCAL VAR socketdev client_socket; LOCAL VAR ROS_joint_trajectory_pt trajectory{MAX_TRAJ_LENGTH}; LOCAL VAR num trajectory_size; PROC main() VAR ROS_msg_joint_traj_pt message; TPWrite "MotionServer: Waiting for connection."; ROS_init_socket server_socket, server_port; ROS_wait_for_client server_socket, client_socket; WHILE ( true ) DO ! Recieve Joint Trajectory Pt Message ROS_receive_msg_joint_traj_pt client_socket, message; trajectory_pt_callback message; ENDWHILE ERROR (ERR_SOCK_TIMEOUT, ERR_SOCK_CLOSED) IF (ERRNO=ERR_SOCK_TIMEOUT) OR (ERRNO=ERR_SOCK_CLOSED) THEN SkipWarn; ! TBD: include this error data in the message logged below? ErrWrite \W, "ROS MotionServer disconnect", "Connection lost. Resetting socket."; ExitCycle; ! restart program ELSE TRYNEXT; ENDIF UNDO IF (SocketGetStatus(client_socket) <> SOCKET_CLOSED) SocketClose client_socket; IF (SocketGetStatus(server_socket) <> SOCKET_CLOSED) SocketClose server_socket; ENDPROC LOCAL PROC trajectory_pt_callback(ROS_msg_joint_traj_pt message) VAR ROS_joint_trajectory_pt point; VAR jointtarget current_pos; VAR ROS_msg reply_msg; point := [message.joints, message.duration]; ! use sequence_id to signal start/end of trajectory download TEST message.sequence_id CASE ROS_TRAJECTORY_START_DOWNLOAD: TPWrite "Traj START received"; trajectory_size := 0; ! Reset trajectory size add_traj_pt point; ! Add this point to the trajectory CASE ROS_TRAJECTORY_END: TPWrite "Traj END received"; add_traj_pt point; ! Add this point to the trajectory activate_trajectory; CASE ROS_TRAJECTORY_STOP: TPWrite "Traj STOP received"; trajectory_size := 0; ! empty trajectory activate_trajectory; StopMove; ClearPath; StartMove; ! redundant, but re-issue stop command just to be safe DEFAULT: add_traj_pt point; ! Add this point to the trajectory ENDTEST ! send reply, if requested IF (message.header.comm_type = ROS_COM_TYPE_SRV_REQ) THEN reply_msg.header := [ROS_MSG_TYPE_JOINT_TRAJ_PT, ROS_COM_TYPE_SRV_REPLY, ROS_REPLY_TYPE_SUCCESS]; ROS_send_msg client_socket, reply_msg; ENDIF ERROR RAISE; ! raise errors to calling code ENDPROC LOCAL PROC add_traj_pt(ROS_joint_trajectory_pt point) IF (trajectory_size = MAX_TRAJ_LENGTH) THEN ErrWrite \W, "Too Many Trajectory Points", "Trajectory has already reached its maximum size", \RL2:="max_size = " + ValToStr(MAX_TRAJ_LENGTH); ELSE Incr trajectory_size; trajectory{trajectory_size} := point; !Add this point to the trajectory ENDIF ENDPROC LOCAL PROC activate_trajectory() WaitTestAndSet ROS_trajectory_lock; ! acquire data-lock TPWrite "Sending " + ValToStr(trajectory_size) + " points to MOTION task"; ROS_trajectory := trajectory; ROS_trajectory_size := trajectory_size; ROS_new_trajectory := TRUE; ROS_trajectory_lock := FALSE; ! release data-lock ENDPROC ENDMODULE

      ROS_stateServer

      MODULE ROS_stateServer ! Software License Agreement (BSD License) ! ! Copyright (c) 2012, Edward Venator, Case Western Reserve University ! Copyright (c) 2012, Jeremy Zoss, Southwest Research Institute ! All rights reserved. ! ! Redistribution and use in source and binary forms, with or without modification, ! are permitted provided that the following conditions are met: ! ! Redistributions of source code must retain the above copyright notice, this ! list of conditions and the following disclaimer. ! Redistributions in binary form must reproduce the above copyright notice, this ! list of conditions and the following disclaimer in the documentation ! and/or other materials provided with the distribution. ! Neither the name of the Case Western Reserve University nor the names of its contributors ! may be used to endorse or promote products derived from this software without ! specific prior written permission. ! ! THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY ! EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES ! OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT ! SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, ! INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED ! TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR ! BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN ! CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY ! WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. LOCAL CONST num server_port := 11002; LOCAL CONST num update_rate := 0.10; ! broadcast rate (sec) LOCAL VAR socketdev server_socket; LOCAL VAR socketdev client_socket; PROC main() TPWrite "StateServer: Waiting for connection."; ROS_init_socket server_socket, server_port; ROS_wait_for_client server_socket, client_socket; WHILE (TRUE) DO send_joints; WaitTime update_rate; ENDWHILE ERROR (ERR_SOCK_TIMEOUT, ERR_SOCK_CLOSED) IF (ERRNO=ERR_SOCK_TIMEOUT) OR (ERRNO=ERR_SOCK_CLOSED) THEN SkipWarn; ! TBD: include this error data in the message logged below? ErrWrite \W, "ROS StateServer disconnect", "Connection lost. Waiting for new connection."; ExitCycle; ! restart program ELSE TRYNEXT; ENDIF UNDO ENDPROC LOCAL PROC send_joints() VAR ROS_msg_joint_data message; VAR jointtarget joints; ! get current joint position (degrees) joints := CJointT(); ! create message message.header := [ROS_MSG_TYPE_JOINT, ROS_COM_TYPE_TOPIC, ROS_REPLY_TYPE_INVALID]; message.sequence_id := 0; message.joints := joints.robax; ! send message to client ROS_send_msg_joint_data client_socket, message; ERROR RAISE; ! raise errors to calling code ENDPROC ENDMODULE

      ROS_motion

      MODULE ROS_motion ! Software License Agreement (BSD License) ! ! Copyright (c) 2012, Edward Venator, Case Western Reserve University ! Copyright (c) 2012, Jeremy Zoss, Southwest Research Institute ! All rights reserved. ! ! Redistribution and use in source and binary forms, with or without modification, ! are permitted provided that the following conditions are met: ! ! Redistributions of source code must retain the above copyright notice, this ! list of conditions and the following disclaimer. ! Redistributions in binary form must reproduce the above copyright notice, this ! list of conditions and the following disclaimer in the documentation ! and/or other materials provided with the distribution. ! Neither the name of the Case Western Reserve University nor the names of its contributors ! may be used to endorse or promote products derived from this software without ! specific prior written permission. ! ! THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY ! EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES ! OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT ! SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, ! INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED ! TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR ! BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN ! CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY ! WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. LOCAL CONST zonedata DEFAULT_CORNER_DIST := z10; LOCAL VAR ROS_joint_trajectory_pt trajectory{MAX_TRAJ_LENGTH}; LOCAL VAR num trajectory_size := 0; LOCAL VAR intnum intr_new_trajectory; PROC main() VAR num current_index; VAR jointtarget target; VAR speeddata move_speed := v10; ! default speed VAR zonedata stop_mode; VAR bool skip_move; ! Set up interrupt to watch for new trajectory IDelete intr_new_trajectory; ! clear interrupt handler, in case restarted with ExitCycle CONNECT intr_new_trajectory WITH new_trajectory_handler; IPers ROS_new_trajectory, intr_new_trajectory; WHILE true DO ! Check for new Trajectory IF (ROS_new_trajectory) init_trajectory; ! execute all points in this trajectory IF (trajectory_size > 0) THEN FOR current_index FROM 1 TO trajectory_size DO target.robax := trajectory{current_index}.joint_pos; skip_move := (current_index = 1) AND is_near(target.robax, 0.1); stop_mode := DEFAULT_CORNER_DIST; ! assume we're smoothing between points IF (current_index = trajectory_size) stop_mode := fine; ! stop at path end ! Execute move command IF (NOT skip_move) MoveAbsJ target, move_speed, \T:=trajectory{current_index}.duration, stop_mode, tool0; ENDFOR trajectory_size := 0; ! trajectory done ENDIF WaitTime 0.05; ! Throttle loop while waiting for new command ENDWHILE ERROR ErrWrite \W, "Motion Error", "Error executing motion. Aborting trajectory."; abort_trajectory; ENDPROC LOCAL PROC init_trajectory() clear_path; ! cancel any active motions WaitTestAndSet ROS_trajectory_lock; ! acquire data-lock trajectory := ROS_trajectory; ! copy to local var trajectory_size := ROS_trajectory_size; ! copy to local var ROS_new_trajectory := FALSE; ROS_trajectory_lock := FALSE; ! release data-lock ENDPROC LOCAL FUNC bool is_near(robjoint target, num tol) VAR jointtarget curr_jnt; curr_jnt := CJointT(); RETURN ( ABS(curr_jnt.robax.rax_1 - target.rax_1) < tol ) AND ( ABS(curr_jnt.robax.rax_2 - target.rax_2) < tol ) AND ( ABS(curr_jnt.robax.rax_3 - target.rax_3) < tol ) AND ( ABS(curr_jnt.robax.rax_4 - target.rax_4) < tol ) AND ( ABS(curr_jnt.robax.rax_5 - target.rax_5) < tol ) AND ( ABS(curr_jnt.robax.rax_6 - target.rax_6) < tol ); ENDFUNC LOCAL PROC abort_trajectory() trajectory_size := 0; ! "clear" local trajectory clear_path; ExitCycle; ! restart program ENDPROC LOCAL PROC clear_path() IF ( NOT (IsStopMoveAct(\FromMoveTask) OR IsStopMoveAct(\FromNonMoveTask)) ) StopMove; ! stop any active motions ClearPath; ! clear queued motion commands StartMove; ! re-enable motions ENDPROC LOCAL TRAP new_trajectory_handler IF (NOT ROS_new_trajectory) RETURN; abort_trajectory; ENDTRAP ENDMODULE

      C 運(yùn)行ROS服務(wù)器

      注意,RAPID運(yùn)行模式為連續(xù)。

      在ROS端編譯完成abb和abb_experimental包,可從github下載。

      支持IRB2400、IRB5400、IRB6600、IRB6640、IRB120、IRB120T和IRB4400等。

      在終端啟動(dòng):

      exbot@relay-Aspire-4741:~$ roslaunch abb_irb120_moveit_config moveit_planning_execution.launch sim:=false robot_ip:=192.168.1.100

      winpc顯示如下:

      rospc顯示如下:

      1 手動(dòng)模式

      程序指針?"PP to Main",Enable使得?"Motors On",點(diǎn)擊運(yùn)行按鈕。即可在rospc端控制機(jī)械臂運(yùn)動(dòng)。

      winpc端:

      rospc端:

      手動(dòng)模式,規(guī)劃執(zhí)行過(guò)程有可能中斷,請(qǐng)查閱相關(guān)文檔。

      2 自動(dòng)模式

      "Motors On"并點(diǎn)擊運(yùn)行模式。

      winpc:

      如果是實(shí)際機(jī)器人,請(qǐng)注意為全速運(yùn)行。

      rospc:

      --

      機(jī)器人

      版權(quán)聲明:本文內(nèi)容由網(wǎng)絡(luò)用戶投稿,版權(quán)歸原作者所有,本站不擁有其著作權(quán),亦不承擔(dān)相應(yīng)法律責(zé)任。如果您發(fā)現(xiàn)本站中有涉嫌抄襲或描述失實(shí)的內(nèi)容,請(qǐng)聯(lián)系我們jiasou666@gmail.com 處理,核實(shí)后本網(wǎng)站將在24小時(shí)內(nèi)刪除侵權(quán)內(nèi)容。

      上一篇:Python爬蟲:頭條小姐姐們都來(lái)給你拜年啦!
      下一篇:華為云IoT設(shè)備接入服務(wù)都有哪些功能?看完給你整的明明白白
      相關(guān)文章
      一本色道久久88亚洲精品综合| 亚洲国产精品日韩av不卡在线| 亚洲av永久无码精品三区在线4| 国产亚洲一区区二区在线 | 亚洲av永久中文无码精品 | 国精无码欧精品亚洲一区| 亚洲中久无码永久在线观看同| 亚洲国产精品一区二区第四页| 亚洲精品无码AV中文字幕电影网站| 亚洲精品亚洲人成在线| 亚洲精品无码国产片| 亚洲爆乳无码专区www| 自拍偷自拍亚洲精品偷一| 亚洲AV无码一区二三区| 亚洲日本在线观看视频| 亚洲色中文字幕无码AV| 亚洲av综合色区| 亚洲精选在线观看| 亚洲国产综合精品| 在线精品亚洲一区二区| 亚洲第一综合天堂另类专| 亚洲av午夜成人片精品电影| 久久久精品国产亚洲成人满18免费网站| 亚洲欧洲精品成人久久奇米网| 国产亚洲精品a在线观看| 亚洲熟妇av一区二区三区漫画 | 亚洲国产aⅴ成人精品无吗| 亚洲第一街区偷拍街拍| 亚洲精品视频免费观看| 国产gv天堂亚洲国产gv刚刚碰| 亚洲不卡中文字幕无码| 久久久亚洲裙底偷窥综合| 亚洲一区二区三区久久| 在线aⅴ亚洲中文字幕| 免费在线观看亚洲| 亚洲精品无码mv在线观看网站| 久久久久久亚洲Av无码精品专口| 亚洲伊人久久精品| 欧美激情综合亚洲一二区| 最新亚洲成av人免费看| 亚洲尹人香蕉网在线视颅 |