Git Product home page Git Product logo

ur5_ros-gazebo's Introduction

Implementation of UR5 pick and place in ROS-Gazebo with a USB cam and vacuum grippers.

This repository demonstrates UR5 pick-and-place in ROS and Gazebo. The UR5 uses a USB cam to detect a red box on a conveyor (ur5_vision.py), and publish its position. UR5 plans its motion (ur5_mp.py) to follow the box. Once the end-effector gets close enough to the box, it approaches the box with vacuum grippers turning on (ur5_gripper.py). Since the vacuum gripper only provides limited force, we placed multiple grippers in order to lift the object.

  • Video demos: Simulation video Hardware video

  • Hardware implementation in UR3: ur3_ROS-hardware

  • Update: based on feebacks from the community, we have made several key changes to this repository on 09/16/2018. Please update your code in case you have trouble reproducing the results.

  • How to cite this repository:

      Huang, L., Zhao, H., Implementation of UR5 pick and place in ROS-Gazebo with a USB cam and vacuum grippers, (2018), GitHub repository, https://github.com/lihuang3/ur5_ROS-Gazebo.git
    

    or BibTex

      @misc{Huang2018,
        author = {Huang, L., Zhao, H.},
        title = {Implementation of UR5 pick and place in ROS-Gazebo with a USB cam and vacuum grippers},
        year = {2018},
        publisher = {GitHub},
        journal = {GitHub repository},
        howpublished = {\url{https://github.com/lihuang3/ur5_ROS-Gazebo.git}}
      }
    

How to use this repository

  • This project was tested in Ubuntu 16.04 with ROS kinetic.
  • Make sure you have installed Python2.7 and some useful libraries/packages, such as Numpy, cv2, etc.
  • Install ROS kinetic, Gazebo, universal robot, Moveit, RViz.
  • Assuming your universal robot workspace is named as ur_ws, download the repository to ur_ws/src/
    $ cd ur_ws/src
    $ git clone https://github.com/lihuang3/ur5_ROS-Gazebo.git
    
  • Under ur_ws/src, there are two folders: one is the official universal_robot, and the other is ur5_ROS-Gazebo. Open file ur5_joint_limited_robot.urdf.xacro under ur_ws/src/universal_robot/ur_description/urdf/, and make the following change to the joint limit:
      shoulder_pan_lower_limit="${-2*pi}" shoulder_pan_upper_limit="${2*pi}"
    
  • In the same directory, make a copy of common.gazebo.xacro and ur5.urdf.xacro in case of any malfunction. These two default files do not include camera and vacuum gripper modules. So we would replace these two files with customized files. Under directory ur_ws/src/ur5_ROS-Gazebo/src/ur_description/, copy common.gazebo.xacro and ur5.urdf.xacro to ur_ws/src/universal_robot/ur_description/urdf/.
  • Build the code under directory ur_ws/,
    $ catkin_make
    $ source devel/setup.bash  
    
  • Run the code with ROS and Gazebo
    $ roslaunch ur5_notebook initialize.launch 
    
  • Things to work on: (1) vacuum grippers only provide limited force for lifting, so we had to use so many of them in order to pick up a light box. If you have any suggestions, please let us know. (2) UR5 motion planning is not in realtime, and hence you can ovserve a non-smooth motion of the end-effect in the camera view.

0. References

######## Warning! The rest of this README is still under construction ###########

1. Universal Robot 5 Installation

Official installation tutorial

The following command lines are for ur5 installation in ros-kinetic

mkdir -p ur5_ws/src
cd ur5_ws/src

# retrieve the sources
git clone -b kinetic-devel https://github.com/ros-industrial/universal_robot.git

cd ~/ur5_ws

# checking dependencies
rosdep install --from-paths src --ignore-src --rosdistro kinetic

# buildin,
catkin_make

# if there is any error, try
# pip uninstall em
# pip install empy

# source this workspace (careful when also sourcing others)
cd ~/ur5_ws
source devel/setup.bash

To run UR5 in Gazebo and rviz (source devel/setup.bash)

roslaunch ur_gazebo ur5.launch limited:=true

roslaunch ur5_moveit_config ur5_moveit_planning_execution.launch sim:=true limited:=true

roslaunch ur5_moveit_config moveit_rviz.launch config:=true

To test UR5 motion, run testmotion.py Look into this link for straight line motion

2. Moveit

Official tutorial

2.0 Install Moveit
sudo apt-get install ros-kinetic-moveit

launch teh Moveit Setup Assistant

roslaunch moveit_setup_assistant setup_assistant.launch

1. Click on the "Create New MoveIt Configuration Package" button,click the "Browse" button, select the xacro file you created in the Previous Chapter, and click on the "Load Files" button.
PATH: /src/universal_robot/ur_description/urdf/ur5.urdf.xacro

2. Go to the "Self-Collisions" tab, and click on the "Regenerate Collision Matrix" button.

3. move to the "Virtual Joints" tab. Here, you will define a virtual joint for the base of the robot. Click the "Add Virtual Joint" button, and set the name of this joint to FixedBase, and the parent to world.

4. open the "Planning Groups" tab and click the "Add Group" button. Now, you will create a new group called manipulator, which uses the KDLKinematicsPlugin.

3. Move Group Python InterFace Tutorial[`Official tutorial`](http://docs.ros.org/indigo/api/moveit_tutorials/html/doc/pr2_tutorials/planning/scripts/doc/move_group_python_interface_tutorial.html)

2.1 Use Moveit Interface

Move Group Interface Tutorial

2.2 Use Moveit in Python

Cartesian Path Planning

Using the ur5 with the MoveIt Motion Planning Framework for quick motion planning. Install the package from package management, and run the MoveIt! planning demo:

$ sudo apt-get install ros-kinetic-ur5-moveit-config

$ roslaunch ur5_moveit_config demo.launch

Our goal is to move the universal robot (ur5) end effector moving in straight line (Cartesian path) with Moveit-Python interface.

References
[1] CMobley7 commented on ros-planning/moveit_commander
[2] homesick-nick UR5CubicInterpolation
[3] Move Group Python Interface Tutorial
[4] ur_modern_driver

3 USB Camera Installation in ROS

Reference link

To list all video devices picked up by the kernel

$ ls -ltrh /dev/video*
$ cd ur5_ws/src

$ git clone https://github.com/bosch-ros-pkg/usb_cam.git

$ cd ..

$ catkin_make

$ source devel/setup.bash

$ roscd usb_cam

# run `roscore` in a new terminal
# Make sure a usb cam is connected

To connect external cam. Locate the usb_cam-test.launch file in folder

cd ~/ur5_ws/src/usb_cam/launch

Change

<param name="video_device" value="/dev/video0" />

to

<param name="video_device" value="/dev/video1" />

From

cd ~/catkin-ws/src/usb_cam/launch run

roslaunch usb_cam-test.launch

If this works, quit the test program, open rviz

rosrun rviz rviz

run the following command in ur5_ws folder (source devel/setup.bash)

rosrun usb_cam usb_cam_node

4. Revolute-Revolute Manipulator Robot

"RRBot, or ''Revolute-Revolute Manipulator Robot'', is a simple 3-linkage, 2-joint arm that we will use to demonstrate various features of Gazebo and URDFs. It essentially a double inverted pendulum and demonstrates some fun control concepts within a simulator."

To get RRBot, clone the gazebo_ros_demos Github repo into the /src folder of your catkin workspace and rebuild your workspace:

cd ~/catkin_ws/src/
git clone https://github.com/ros-simulation/gazebo_ros_demos.git
cd ..
catkin_make
source devel/setup.bash

Quick start

Rviz:

roslaunch rrbot_description rrbot_rviz.launch

Gazebo:

roslaunch rrbot_gazebo rrbot_world.launch

ROS Control:

roslaunch rrbot_control rrbot_control.launch

Example of Moving Joints:

rostopic pub /rrbot/joint2_position_controller/command std_msgs/Float64 "data: -0.9"

5. Using Gazebo Camera Plugins

roslaunch ur_description ur5_upload.launch
roslaunch ur_description test.launch

You probably need to install urdf_tutorial:

cd ~/catkin_ws/src/
git clone https://github.com/ros/urdf_tutorial
cd ..
catkin_make
source devel/setup.bash

In rviz, the first task is to choose the frame of reference for the visualization. In left panel, Global Options/Fixed Frame, choose a proper frame (e. g. world)

Next, we want to view the 3D model of the robot. To accomplish this, we will insert an instance of the robot model plugin To add the robot model to the rviz scene, click the “Add” button and choose RobotModel

To test UR5 USB cam, run testvision.py

5. gazebo world Launch

launch gazebo files :

roslaunch ur5_notebook initialize.launch

change object pose and twist with command line:

rosservice call /gazebo/set_model_state '{model_state: { model_name: red_box, pose: { position: { x: 0, y: 0 ,z: 1 }, orientation: {x: 0, y: 0, z: 0, w: 0 } }, twist: { linear: {x: 0.1 , y: 0 ,z: 0 } , angular: { x: 0.0 , y: 0 , z: 0.0 } } , reference_frame: world } }'

6. openCV

7. ariac

ur5_ros-gazebo's People

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

ur5_ros-gazebo's Issues

How can i move my arm and turn the camera when all models are present

Hi,lihuang3,when i run roslaunch ur5_notebook initialize.launch i can see the whole models,but my arm can't move ,and the camera window can appear but there is no image.Also there ia an error :

[ur5_mp-15] process has died [pid 3924, exit code 1, cmd /home/just17/catkin_ws/src/ur5_ROS-Gazebo-master/ur5_mp.py /follow_joint_trajectory:=/arm_controller/follow_joint_trajectory __name:=ur5_mp __log:=/home/just17/.ros/log/3f6e8a5e-8206-11e9-a337-000c2900ddbe/ur5_mp-15.log].
log file: /home/just17/.ros/log/3f6e8a5e-8206-11e9-a337-000c2900ddbe/ur5_mp-15
.log
*

I am very intersted about it and try many times . how can i deal with this error and move my arm ? Looking forward to your reply.Thank you very much

Failed to build tree: child link [base_link] of joint [world_joint] not found

Hi all hope you all are doing great.

I have this error:

not single time but multiple times. also some more:

[robot_state_publisher-4] process has died [pid 10139, exit code 255, cmd /opt/ros/kinetic/lib/robot_state_publisher/robot_state_publisher __name:=robot_state_publisher __log:=/home/ros/.ros/log/eed9c1bc-a5ca-11ec-a955-d80f997b25c9/robot_state_publisher-4.log]. log file: /home/ros/.ros/log/eed9c1bc-a5ca-11ec-a955-d80f997b25c9/robot_state_publisher-4.log [ur5_mp-14] process has died [pid 10216, exit code 1, cmd /home/ros/ur_ws/src/ur5_ROS-Gazebo/ur5_mp.py /follow_joint_trajectory:=/arm_controller/follow_joint_trajectory __name:=ur5_mp __log:=/home/ros/.ros/log/eed9c1bc-a5ca-11ec-a955-d80f997b25c9/ur5_mp-14.log]. log file: /home/ros/.ros/log/eed9c1bc-a5ca-11ec-a955-d80f997b25c9/ur5_mp-14.log

I am using this git repository:

https://github.com/lihuang3/ur5_ROS-G...

I tried following this tutorial , I had an issue of ur_hardware_interface which this git addresses and I was able to solve it. the error new I am facing (i.e. failed to build tree), i have searched it and found solutions on it but not specific to my case and theirs dont apply to my case.

here is my initialize.launch :

and here is my ur5_joint_limited_robot.urdf.xacro: (modified according to the git)

<robot <a="" href="http://xmlns:xacro="http://wiki.ros.org/xacro">xmlns:xacro="http://wiki.ros.org/xacro" name="ur5" ><="" p="">

<xacro:arg name="transmission_hw_interface" default="hardware_interface/PositionJointInterface"/>

<xacro:include filename="$(find ur_description)/urdf/common.gazebo.xacro"/>

<xacro:include filename="$(find ur_description)/urdf/ur5.urdf.xacro"/>

<xacro:macro name="ur5_robot" params="prefix joint_limited shoulder_pan_lower_limit:=${-2pi} shoulder_pan_upper_limit:=${2pi} shoulder_lift_lower_limit:=${-pi} shoulder_lift_upper_limit:=${pi} elbow_joint_lower_limit:=${-pi} elbow_joint_upper_limit:=${pi} wrist_1_lower_limit:=${-pi} wrist_1_upper_limit:=${pi} wrist_2_lower_limit:=${-pi} wrist_2_upper_limit:=${pi} wrist_3_lower_limit:=${-pi} wrist_3_upper_limit:=${pi} transmission_hw_interface:=hardware_interface/PositionJointInterface"/>

Please advise with this issue, also Please answer these questions: 1. why do a failed to build tree error occures? 2. how doee one ensure a urdf is correctly made? 3. Any tips on how to remove the warning: inconsistent namespace redefinitions for xmlns:xacro

I know we can run things with warning so you may not answer the last question.

The condition to determine the target position overlapping with the initial position

In line 114 of ur5_mp.py , the condition to determine the target position overlapping with the initial position is
np.sqrt((wpose.position.x-start_pose.position.x)**2+(wpose.position.x-start_pose.position.x)**2+(wpose.position.x-start_pose.position.x)**2)<0.1

It should consider x, y, z coordinates instead of x three times, isn't is?
np.sqrt((wpose.position.**x**-start_pose.position.**x**)**2+(wpose.position.**y**-start_pose.position.**y**)**2+(wpose.position.**z**-start_pose.position.**z**)**2)<0.1

which file should I execute to control the robot arm to grasp the red box

Hi,lihuang3.Thank you very much for your excellent work.Still,I would like to know how to let the robot arm move to grasp the red box after the "roslaunch ur5_notebook initialize.launch".
I am still a rockie to this ROS area.Can you tell me which file should I execute? Looking forward to your reply.Thank you very much

Gazebo vacuum gripper plugin

Hi! I have seen your video of pick and place demo using UR5 and vacuum gripper from youtube.
This is a nice work and we are very interesting!!

Recently we want to use vacuum gripper in gazebo simulator, but we get some problem.

We can load plugin to simulator and trigger it, but sometime vacuum gripper can’t grasp object in gazebo.

We’d like to ask you some questions:

  1. What reason make you increase amount of vacuum gripper becoming nine grippers?
  2. What kind of help would do this?
  3. What are the functions of the following two tags for gazebo vacuum gripper plugin?
<maxDistance>0.05</maxDistance>
<minDistance>0.01</minDistance>

Thanks for providing useful example on github!

AttributeError: ur5_mp instance has no attribute 'arm'

Hallo LiHuang, I am facing a problem when running the roslaunch method. All the simulation and gazebo launched well. But I am facing a problem at the ur5_mp.py file: I am really new to ROS. Please help. I really need help because I am really desperate.

Traceback (most recent call last): File "/home/mohan/dd_ws/src/ur5_ROS-Gazebo/ur5_mp.py", line 374, in <module> mp=ur5_mp() File "/home/mohan/dd_ws/src/ur5_ROS-Gazebo/ur5_mp.py", line 63, in __init__ self.arm = moveit_commander.MoveGroupCommander('manipulator') File "/opt/ros/kinetic/lib/python2.7/dist-packages/moveit_commander/move_group.py", line 52, in __init__ self._g = _moveit_move_group_interface.MoveGroupInterface(name, robot_description, ns) RuntimeError: Unable to connect to move_group action server 'move_group' within allotted time (5s) [INFO] [1596241103.351390, 0.000000]: Stopping the robot Traceback (most recent call last): File "/opt/ros/kinetic/lib/python2.7/dist-packages/rospy/core.py", line 466, in signal_shutdown h() File "/home/mohan/dd_ws/src/ur5_ROS-Gazebo/ur5_mp.py", line 153, in cleanup self.arm.stop() AttributeError: ur5_mp instance has no attribute 'arm'

`[ INFO] [1596241103.819728500, 6.237000000]: Using planning interface 'OMPL'
[ INFO] [1596241103.919725800, 6.320000000]: Param 'default_workspace_bounds' was not set. Using default value: 10
[ INFO] [1596241104.057005900, 6.331000000]: Param 'start_state_max_bounds_error' was set to 0.1
[ INFO] [1596241104.172064400, 6.397000000]: Param 'start_state_max_dt' was not set. Using default value: 0.5
[ INFO] [1596241104.281793600, 6.419000000]: Param 'start_state_max_dt' was not set. Using default value: 0.5
[ INFO] [1596241104.386338100, 6.480000000]: Param 'jiggle_fraction' was set to 0.05
[ INFO] [1596241104.464261100, 6.490000000]: Param 'max_sampling_attempts' was not set. Using default value: 100
[ INFO] [1596241104.508344700, 6.490000000]: Using planning request adapter 'Add Time Parameterization'
[ INFO] [1596241104.563671800, 6.535000000]: Using planning request adapter 'Fix Workspace Bounds'
[ INFO] [1596241104.659348900, 6.535000000]: Using planning request adapter 'Fix Start State Bounds'
[ INFO] [1596241104.762128000, 6.548000000]: Using planning request adapter 'Fix Start State In Collision'
[ INFO] [1596241104.864209500, 6.575000000]: Using planning request adapter 'Fix Start State Path Constraints'
[ur5_mp-15] process has died [pid 22712, exit code 1, cmd /home/mohan/dd_ws/src/ur5_ROS-Gazebo/ur5_mp.py /follow_joint_trajectory:=/arm_controller/follow_joint_trajectory __name:=ur5_mp __log:=/root/.ros/log/6ea9e25e-d38c-11ea-92c3-00155d73c6ba/ur5_mp-15.log].
log file: /root/.ros/log/6ea9e25e-d38c-11ea-92c3-00155d73c6ba/ur5_mp-15*.log
[ WARN] [1596241122.326145000, 12.571000000]: Waiting for /follow_joint_trajectory to come up
[ WARN] [1596241139.949147500, 18.616000000]: Waiting for /follow_joint_trajectory to come up
[ INFO] [1596241153.339214100, 22.642000000]: y position of new box: 0.0950119
,

[ INFO] [1596241218.368347700, 43.517000000]: red_blocks_1 has been spawned
[ INFO] [1596241218.536115200, 43.585000000]: ApplyBodyWrench: reference_frame is empty/world/map, using inertial frame, transferring from body relative to inertial frame
[ INFO] [1596241218.582610100, 43.591000000]: red_blocks_1 speed initialized
[ INFO] [1596241218.654149700, 43.603000000]:
[ERROR] [1596241237.322624600, 49.329000000]: Action client not connected: /follow_joint_trajectory
[ INFO] [1596241237.844478400, 49.491000000]: Returned 0 controllers in list
[ INFO] [1596241239.845947700, 50.153000000]: Trajectory execution is managing controllers`

can't locate node [ur5_vision.py] in package [ur5_notebook]

Hello,
When I run the roslauch ur5_notebook initialize.launch,the error occur as follows:
ERROR: cannot launch node of type [ur5_notebook/ur5_vision.py]: can't locate node [ur5_vision.py] in package [ur5_notebook]
ERROR: cannot launch node of type [ur5_notebook/ur5_mp.py]: can't locate node [ur5_mp.py] in package [ur5_notebook]
ERROR: cannot launch node of type [ur5_notebook/ur5_gripper.py]: can't locate node [ur5_gripper.py] in package [ur5_notebook]
why? I run the same code in another computer is normal.

vacuum gripper plugin is not working

image

I was looking for a solution based on the last post(#47). As a result of searching for the cause of not sticking to the wall, it was inferred that the vacuum gripper's plugin did not work properly, and it was confirmed through the test model (In the picture above, the red cylinder is the gripper link, and this link should pull the blue box).

In the picture above, can you tell me where I need to improve for the gripper plugin to work? The source code is below.

----urdf.xacro code-----

image

----gazebo.xacro code-----
image

----gripper.py code-----
image

error when roslunch ur5_notebook initialize.launch

hello,lihuang,when i replace these two files with customized files. Under directory ur_ws/src/ur5_ROS-Gazebo/src/ur_description/, copy common.gazebo.xacro and ur5.urdf.xacro to ur_ws/src/universal_robot/ur_description/urdf/.then i roslunch ur5_notebook initialize.launch,there ia an error makes can not start the gazebo,i am so confused,would you help me,folling is the detail about error:

###(ERROR) Invalid parameter "transmission_hw_interface" None ### None
when instantiating macro: ur5_robot (/home/hourui/catkin_ws/src/universal_robot-kinetic-devel/universal_robot-kinetic-devel/ur_description/urdf/ur5.urdf.xacro)
in file: /home/hourui/catkin_ws/src/universal_robot-kinetic-devel/universal_robot-kinetic-devel/ur_description/urdf/ur5_joint_limited_robot.urdf.xacro

{ERROR}while processing /home/hourui/catkin_ws/src/universal_robot-kinetic-devel/universal_robot-kinetic-devel/ur_description/launch/ur5_upload.launch:

Invalid tag: Cannot load command parameter [robot_description]: command [/opt/ros/kinetic/lib/xacro/xacro --inorder '/home/hourui/catkin_ws/src/universal_robot-kinetic-devel/universal_robot-kinetic-devel/ur_description/urdf/ur5_joint_limited_robot.urdf.xacro' transmission_hw_interface:=hardware_interface/PositionJointInterface] returned with code [2].

Param xml is
The traceback for the exception was written to the log file

waiting for your help,grateful about you!

Red box problem

I notised that there is nly a publisher for cylinder position but the model in the gazebo is red box?

questions about dependence between packages

when I run "rosrun ur5_notebook initialize.launch", it can work. But I find "initialize.launch" does not belong to "ur5_notebook" package. Maybe, I think, this is because of the dependence issue.
So I try " rosrun ur5_ROS-Gazebo initialize.launch", it fails. But this launch file is in the "ur5_ROS-Gazebo" package.

Could you help me figure it out?

Implementation of vacuum suction using vacuum gripper

wallfall1

Hello. I'm in the process of implementing vacuum suction by referring to some of the open sources here. I referenced a lot in urdf, gazebo's xacro, and node files, but the object should stick to the wall, but it keeps falling off. I'll give you the attached file, can you take a look? I'd like to attach the source code, but it's too many, so I'm attaching the package files I'm working on.

wallclimb.zip

The parts to look at are:
climbbot.urdf.xacro
climbbot.gazebo.xacro
climbbot_gripper.py
wall_test1.launch (gazebo executable file)

how to run it without gui

ai title, i want to run this demo on a server, and there is no gui. it seems like the camera node doesn't work. what should i do to make the camera work and thus the robot can pick the box

how to control the arm speed in gazebo

hey,lihuang!I just want to control the speed of the arm in gazebo by the jacobian matrix.i find you in blocks_spawner.cpp to control the red_box speed,do you have some examples just use code to control the speed of control in gazebo? I am in this trouble for a long time.

Invalid parameter "transmission_hw_interface"

is there someone meet the same problem?
I guess it's because universal-robot official add transmission_hw_interface which cause the ur5.urdf.xacro is not consistant with the u5_joint_limited_robot.urdf.xacro.
when i delete the hw_interface, i met another problem "XML parsing error: mismatched tag: line 66, column 4

The msg.data always false

Hi hope you all well.
When i run the code i got warn about the complete gripper_status is unknown, missing gripper_joint --- gripper_joint8.
and I test the gripper.py the msg.data always show as false. I don't know if my robot is not set up well from moveit-config or did I miss something? Thank you!

不执行抓取动作

您好
程序执行没有报错,可以看到已经检测到了红色目标的坐标位置
但是检测到后,机械臂并不执行抓取,而是直接掉头转向筐然后保持不动
请问这个是什么问题导致的尼

How can I get the same goal as gif

Hello Lihuang:
I had followed your steps and installed all the package which in the readme, but how can I get the same effect after I had executed the step of "roslaunch ur5_notebook initialize.launch".But the ur5 remained static, it can't grasp the red box.

[rospack] Error: package 'ur5_ROS-Gazebo' not found

Hi!

I am having problems running testmotion.py.
This is what happens:


laurah@laurah-HP-EliteBook-840-G1:~/catkin_ws$ catkin_make
Base path: /home/laurah/catkin_ws
Source space: /home/laurah/catkin_ws/src
Build space: /home/laurah/catkin_ws/build
Devel space: /home/laurah/catkin_ws/devel
Install space: /home/laurah/catkin_ws/install
####
#### Running command: "make cmake_check_build_system" in "/home/laurah/catkin_ws/build"
####
####
#### Running command: "make -j4 -l4" in "/home/laurah/catkin_ws/build"
####
[  0%] Built target std_msgs_generate_messages_cpp
[  0%] Built target _ur_msgs_generate_messages_check_deps_IOStates
[  0%] Built target _ur_msgs_generate_messages_check_deps_MasterboardDataMsg
[  0%] Built target _ur_msgs_generate_messages_check_deps_Analog
[  0%] Built target _ur_msgs_generate_messages_check_deps_RobotModeDataMsg
[  0%] Built target _ur_msgs_generate_messages_check_deps_Digital
[  0%] Built target _ur_msgs_generate_messages_check_deps_ToolDataMsg
[  0%] Built target _ur_msgs_generate_messages_check_deps_SetIO
[  0%] Built target std_msgs_generate_messages_nodejs
[  0%] Built target _ur_msgs_generate_messages_check_deps_RobotStateRTMsg
[  0%] Built target std_msgs_generate_messages_py
[  0%] Built target std_msgs_generate_messages_lisp
[  0%] Built target std_msgs_generate_messages_eus
[  0%] Built target _ur_msgs_generate_messages_check_deps_SetPayload
[  1%] Built target blocks_poses_publisher
[  3%] Built target blocks_spawner
[  5%] Built target ur_driver_gencfg
[  5%] Built target industrial_msgs_generate_messages_lisp
[  5%] Built target _ur5_notebook_generate_messages_check_deps_Tracker
[  5%] Built target _ur5_notebook_generate_messages_check_deps_blocks_poses
[  5%] Built target _catkin_empty_exported_target
[  5%] Built target sensor_msgs_generate_messages_py
[  5%] Built target std_srvs_generate_messages_eus
[  5%] Built target geometry_msgs_generate_messages_py
[  5%] Built target geometry_msgs_generate_messages_eus
[  5%] Built target roscpp_generate_messages_cpp
[  5%] Built target sensor_msgs_generate_messages_nodejs
[  5%] Built target sensor_msgs_generate_messages_cpp
[  5%] Built target trajectory_msgs_generate_messages_lisp
[  5%] Built target trajectory_msgs_generate_messages_eus
[  5%] Built target trajectory_msgs_generate_messages_py
[  5%] Built target sensor_msgs_generate_messages_eus
[  5%] Built target geometry_msgs_generate_messages_cpp
[  5%] Built target std_srvs_generate_messages_cpp
[  5%] Built target trajectory_msgs_generate_messages_cpp
[  5%] Built target rosgraph_msgs_generate_messages_lisp
[  5%] Built target roscpp_generate_messages_nodejs
[  5%] Built target rosgraph_msgs_generate_messages_py
[  5%] Built target trajectory_msgs_generate_messages_nodejs
[  5%] Built target geometry_msgs_generate_messages_lisp
[  5%] Built target std_srvs_generate_messages_lisp
[  5%] Built target std_srvs_generate_messages_py
[  5%] Built target roscpp_generate_messages_lisp
[  5%] Built target roscpp_generate_messages_eus
[  5%] Built target roscpp_generate_messages_py
[  5%] Built target rosgraph_msgs_generate_messages_cpp
[  5%] Built target rosgraph_msgs_generate_messages_eus
[  5%] Built target std_srvs_generate_messages_nodejs
[  5%] Built target rosgraph_msgs_generate_messages_nodejs
[  5%] Built target geometry_msgs_generate_messages_nodejs
[  5%] Built target sensor_msgs_generate_messages_lisp
[  5%] Built target industrial_msgs_generate_messages_cpp
[  5%] Built target controller_manager_msgs_generate_messages_nodejs
[  5%] Built target control_msgs_generate_messages_nodejs
[  5%] Built target tf_generate_messages_eus
[  5%] Built target control_msgs_generate_messages_py
[  5%] Built target actionlib_msgs_generate_messages_py
[  5%] Built target actionlib_msgs_generate_messages_lisp
[  5%] Built target control_msgs_generate_messages_eus
[  5%] Built target actionlib_msgs_generate_messages_eus
[  5%] Built target industrial_msgs_generate_messages_eus
[  5%] Built target actionlib_generate_messages_lisp
[  5%] Built target actionlib_generate_messages_eus
[  5%] Built target tf_generate_messages_cpp
[  5%] Built target controller_manager_msgs_generate_messages_cpp
[  5%] Built target controller_manager_msgs_generate_messages_eus
[  5%] Built target tf2_msgs_generate_messages_eus
[  5%] Built target actionlib_generate_messages_py
[  5%] Built target actionlib_generate_messages_cpp
[  5%] Built target tf2_msgs_generate_messages_py
[  5%] Built target control_msgs_generate_messages_lisp
[  5%] Built target actionlib_msgs_generate_messages_nodejs
[  5%] Built target controller_manager_msgs_generate_messages_lisp
[  5%] Built target control_msgs_generate_messages_cpp
[  5%] Built target industrial_msgs_generate_messages_py
[  5%] Built target industrial_msgs_generate_messages_nodejs
[  5%] Built target tf_generate_messages_lisp
[  5%] Built target tf2_msgs_generate_messages_nodejs
[  5%] Built target tf_generate_messages_nodejs
[  5%] Built target tf_generate_messages_py
[  5%] Built target controller_manager_msgs_generate_messages_py
[  5%] Built target tf2_msgs_generate_messages_lisp
[  5%] Built target tf2_msgs_generate_messages_cpp
[  7%] Built target ur_hardware_interface
[  7%] Built target actionlib_generate_messages_nodejs
[  7%] Built target actionlib_msgs_generate_messages_cpp
[ 10%] Built target ur10_kin
[ 13%] Built target ur5_kin
[ 15%] Built target ur3_kin
[ 25%] Built target ur_msgs_generate_messages_cpp
[ 34%] Built target ur_msgs_generate_messages_nodejs
[ 46%] Built target ur_msgs_generate_messages_py
[ 55%] Built target ur_msgs_generate_messages_lisp
[ 65%] Built target ur_msgs_generate_messages_eus
[ 68%] Built target ur5_notebook_generate_messages_nodejs
[ 71%] Built target ur5_notebook_generate_messages_py
[ 72%] Built target ur5_notebook_generate_messages_cpp
[ 73%] Built target ur5_notebook_generate_messages_lisp
[ 77%] Built target ur5_notebook_generate_messages_eus
[ 78%] Built target ur10_moveit_plugin
[ 96%] Built target ur_driver
[ 98%] Built target ur5_moveit_plugin
[100%] Built target ur3_moveit_plugin
[100%] Built target ur_msgs_generate_messages
[100%] Built target ur5_notebook_generate_messages
laurah@laurah-HP-EliteBook-840-G1:~/catkin_ws$ source devel/setup.bash
laurah@laurah-HP-EliteBook-840-G1:~/catkin_ws$ rosrun ur5_ROS-Gazebo testmotion.py
[rospack] Error: package 'ur5_ROS-Gazebo' not found
laurah@laurah-HP-EliteBook-840-G1:~/catkin_ws$ 

I installed the package in my catkin_ws/src folder using "git clone https://github.com/lihuang3/ur5_ROS-Gazebo.git"

Why won't it find the package?

Hello,we met a issues when catkin_make.How should we do?

In file included from /home/vr715/ur_ws/src/universal_robot/ur_kinematics/include/ur_kinematics/ur_moveit_plugin.h:100:0,
from /home/vr715/ur_ws/src/universal_robot/ur_kinematics/src/ur_moveit_plugin.cpp:88:
/opt/ros/melodic/include/moveit/kinematics_base/kinematics_base.h:339:34: note: declared here
MOVEIT_DEPRECATED virtual void setValues(const std::string& robot_description, const std::string& group_name,
^~~~~~~~~
[ 97%] Linking CXX shared library /home/vr715/ur_ws/devel/lib/libur10_moveit_plugin.so
[ 98%] Linking CXX shared library /home/vr715/ur_ws/devel/lib/libur3_moveit_plugin.so
[100%] Linking CXX shared library /home/vr715/ur_ws/devel/lib/libur5_moveit_plugin.so
[100%] Built target ur10_moveit_plugin
[100%] Built target ur3_moveit_plugin
[100%] Built target ur5_moveit_plugin
Makefile:140: recipe for target 'all' failed
make: *** [all] Error 2
Invoking "make -j16 -l16" failed

Unable to launch intialize.launch ur5_upload.launch missing

darshit@darshit-Inspiron-5558:~/catkin_ws$ roslaunch ur5_notebook initialize.launch
... logging to /home/darshit/.ros/log/15b67b32-7202-11ed-a9a0-297a8c4ae0cd/roslaunch-darshit-Inspiron-5558-18629.log
Checking log directory for disk usage. This may take a while.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

RLException: while processing /home/darshit/catkin_ws/src/universal_robot/ur_description/launch/ur5_upload.launch:
Invalid roslaunch XML syntax: [Errno 2] No such file or directory: '/home/darshit/catkin_ws/src/universal_robot/ur_description/launch/ur5_upload.launch'
The traceback for the exception was written to the log file

The above is the error which occurrs when I run the command. Where can I get this file? and How to resolver it?

Hi, I also use ROS-melodic, facing the same problem. Did you resovle that?

hello, i use melodic,but error occurs。
RLException: while processing /home/xiong/ur5_ws/src/universal_robot/ur_description/launch/ur5_upload.launch:
Invalid tag: Cannot load command parameter [robot_description]: command [['/opt/ros/melodic/lib/xacro/xacro', '--inorder', '/home/xiong/ur5_ws/src/universal_robot/ur_description/urdf/ur5_joint_limited_robot.urdf.xacro', 'transmission_hw_interface:=hardware_interface/PositionJointInterface']] returned with code [2].

Param xml is
The traceback for the exception was written to the log file

i hope someone can help me,please

Originally posted by @learningxiaobai in #13 (comment)

Missing 'common.gazebo.xacro' file from description/urdf folder.

Hello,

I hope you and everyone in your family are doing great. I have followed the installation instructions to setup the workspace for this repository, however I was encountered with the following error when attempting to launch the file of the simulation:

no such file or directory: /home/cocp5/catkin_ws/src/universal_robot/ur_description/urdf/common.gazebo.xacro [Errno 2] No such file or directory: '/home/cocp5/catkin_ws/src/universal_robot/ur_description/urdf/common.gazebo.xacro

Further to that I also received the following message:

o such file or directory: /home/cocp5/catkin_ws/src/universal_robot/ur_description/urdf/common.gazebo.xacro [Errno 2] No such file or directory: '/home/cocp5/catkin_ws/src/universal_robot/ur_description/urdf/common.gazebo.xacro

In order to resolve this I renamed the ur.xacro file in the descriptio/urdf folder to have the same name as the one it was not able to find based on the error, however that did not work either since I receivd then the following error:

o such file or directory: /home/cocp5/catkin_ws/src/universal_robot/ur_description/urdf/common.gazebo.xacro [Errno 2] No such file or directory: '/home/cocp5/catkin_ws/src/universal_robot/ur_description/urdf/common.gazebo.xacro

Could you please help me debug this?

Thank you in advance for all your valuable help and support!

Kind reagards,

Christos Peridis

The robot arm doesn't pick the boxes

Hi, lihuang. I'm new to ROS and interested in your project,
because I wanna simulate picking process with vacuum gripper.

But when I launch initialize.launch, the robot arm doesn't pick the red boxes though it detects them.
It just goes to the placing position with empty hand and stays still.

I think the error messages involved are these.

[ INFO] [1591681700.942636701, 17.686000000]: Received request to compute Cartesian path
[ERROR] [1591681700.942913192, 17.686000000]: TF Problem: Invalid argument "/base_link" passed to lookupTransform argument target_frame in tf2 frame_ids cannot start with a '/' like:
[ERROR] [1591681700.942986402, 17.686000000]: Error encountered transforming waypoints to frame 'world'
[INFO] [1591681700.943591, 17.687000]: Path planning failed

As I'm using melodic, I thought there could be some errors but can you help me with it?

Screenshot from 2020-06-09 00-00-58
Screenshot from 2020-06-09 00-01-04

What is mean of this code?

Hello LiHuang:
I can't understand this code as follows:

def tracking_callback(self, msg):
    self.track_flag = msg.flag1
    self.cx = msg.x
    self.cy = msg.y
    self.error_x = msg.error_x
    self.error_y = msg.error_y
    if len(self.pointx)>9:
        self.track_flag = True
    if self.phase == 2:
        self.track_flag = False
        self.phase = 1
    if (self.track_flag and -0.6 < self.waypoints[0].position.x and self.waypoints[0].position.x < 0.6):
        self.execute()
        self.default_pose_flag = False
    else:
        if not self.default_pose_flag:
            self.track_flag = False
            self.execute()
            self.default_pose_flag = True

def execute(self):
    if self.track_flag:
        # Get the current pose so we can add it as a waypoint
        start_pose = self.arm.get_current_pose(self.end_effector_link).pose
        # Initialize the waypoints list
        self.waypoints= []
        # Set the first waypoint to be the starting pose
        # Append the pose to the waypoints list
        wpose = deepcopy(start_pose)
        # wpose.position.x = -0.5215
        # wpose.position.y = 0.2014
        # wpose.position.z = 0.4102
        if len(self.pointx)>8:
            if len(self.pointx)==9:
                x_speed = np.mean(np.asarray(self.pointx[4:8]) - np.asarray(self.pointx[3:7]))
                wpose.position.x += 2 * x_speed
                wpose.position.z = 0.05

   what's mean of the self.phase and the self.pointsx. And in the tracking_callback(), There are four "if" statements,I can't understand how do these three conditional statements work?

TF Problem:

i faced a problem in melodic
TF Problem: Invalid argument "/base_link" passed to lookupTransform argument target_frame in tf2 frame_ids cannot start with a '/' like:

I fix it by changing reference_farame = "/base_link" to "reference_farame = "base_link" in ur_mp.py

catkin_make failed

Hi, I'm getting this error whenever I try to build the file:

[ 57%] Building CXX object ur5_ROS-Gazebo/CMakeFiles/blocks_poses_publisher.dir/blocks_poses_publisher.cpp.o
/home/gg/ur_ws/src/ur5_ROS-Gazebo/blocks_poses_publisher.cpp:14:39: fatal error: ur5_notebook/blocks_poses.h: No such file or directory
compilation terminated.
ur5_ROS-Gazebo/CMakeFiles/blocks_poses_publisher.dir/build.make:62: recipe for target 'ur5_ROS-Gazebo/CMakeFiles/blocks_poses_publisher.dir/blocks_poses_publisher.cpp.o' failed
make[2]: *** [ur5_ROS-Gazebo/CMakeFiles/blocks_poses_publisher.dir/blocks_poses_publisher.cpp.o] Error 1
CMakeFiles/Makefile2:1747: recipe for target 'ur5_ROS-Gazebo/CMakeFiles/blocks_poses_publisher.dir/all' failed
make[1]: *** [ur5_ROS-Gazebo/CMakeFiles/blocks_poses_publisher.dir/all] Error 2
Makefile:138: recipe for target 'all' failed
make: *** [all] Error 2
Invoking "make -j1 -l1" failed

This occurred after I have completed this part and perform catkin_make:

In the same directory, make a copy of common.gazebo.xacro and ur5.urdf.xacro in case of any malfunction. These two default files do not include camera and vacuum gripper modules. So we would replace these two files with customized files. Under directory ur_ws/src/ur5_ROS-Gazebo/src/ur_description/, copy common.gazebo.xacro and ur5.urdf.xacro to ur_ws/src/universal_robot/ur_description/urdf/.

Can someone please help me out?
I need to get the installation done asap.

Using Two Robots for the Pick and Place Task

Hello,
The code seems to work perfectly but now I am planning to use two UR5 instead one for the same task.
I can successfully launch two robots but then it doesn't do anything.

Here is my launch file for launching the two robots

   <?xml version="1.0"?>
<launch>
  <param name="red_box_path" type="str" value="$(find ur5_notebook)/urdf/red_box.urdf"/>
  <param name="/use_sim_time" value="true" />
  <arg name="robot_name"/>
  <arg name="init_pose"/>

  <arg name="limited" default="true"/>
  <arg name="paused" default="false"/>
  <arg name="gui" default="true"/>
  <arg name="debug" default="false" />
  <arg name="sim" default="true" />
  <arg name="transmission_hw_interface" default="hardware_interface/PositionJointInterface" />
  

  <!-- startup simulated world -->
  <include file="$(find gazebo_ros)/launch/empty_world.launch">
    <arg name="world_name" default="worlds/empty.world"/>
    <arg name="paused" value="$(arg paused)"/>
    <arg name="gui" value="$(arg gui)"/>
  </include>

  <!-- spawn the conveyor_belt in gazebo -->
  <node name="spawn_conveyor_belt" pkg="gazebo_ros" type="spawn_model" args="-file $(find ur5_notebook)/urdf/conveyor_belt.urdf -urdf -model conveyor_belt" />
  <!-- spawn the conveyor_belt in gazebo -->
  <node name="bin" pkg="gazebo_ros" type="spawn_model" args="-file $(find ur5_notebook)/urdf/bin.urdf -urdf -model bin -y 0.8 -x -0.5 -z 0.05" />
  <!-- the red blocks spawner node -->
  <node name="blocks_spawner" pkg="ur5_notebook" type="blocks_spawner" output="screen" />

  <!-- the cylinder poses publisher node -->
  <node name="blocks_poses_publisher" pkg="ur5_notebook" type="blocks_poses_publisher" output="screen" />

  <!-- spwan ur5 -->
  <!-- send robot urdf to param server -->
  <group ns="robot1">
    <param name="tf_prefix" value="robot1_tf" />
        <include file="$(find ur_gazebo)/launch/ur5.launch">
                <arg name="init_pose" value="-z 0.2 -y 0.7"/>
                <arg name="robot_name" value="robot1"/>
        </include>

        <include file="$(find ur5_moveit_config)/launch/move_group.launch">
          <arg name="limited" default="$(arg limited)"/>
          <arg name="debug" default="$(arg debug)" />
        </include>
        
        <node name="ur5_vision" pkg="ur5_notebook" type="ur5_vision.py" output="screen" />
        <node name="ur5_mp" pkg="ur5_notebook" type="ur5_mp.py" output="screen" />
        <node name="ur5_gripper" pkg="ur5_notebook" type="ur5_gripper.py" output="screen"/>

        <remap if="$(arg sim)" from="follow_joint_trajectory" to="arm_controller/follow_joint_trajectory"/>

        <!-- Remap follow_joint_trajectory -->

        <!-- Launch moveit -->

          <!-- the cylinder poses publisher node -->

  </group>

  <group ns="robot2">
    <param name="tf_prefix" value="robot2_tf" />
        <include file="$(find ur_gazebo)/launch/ur5.launch">
                <arg name="init_pose" value="-z 0.2 -y -0.7"/>
                <arg name="robot_name" value="robot2"/>
        </include>

        <include file="$(find ur5_moveit_config)/launch/move_group.launch">
          <arg name="limited" default="$(arg limited)"/>
          <arg name="debug" default="$(arg debug)" />
        </include>
        
        <node name="ur5_vision" pkg="ur5_notebook" type="ur5_vision.py" output="screen" />
        <node name="ur5_mp" pkg="ur5_notebook" type="ur5_mp.py" output="screen" />
        <node name="ur5_gripper" pkg="ur5_notebook" type="ur5_gripper.py" output="screen"/>

        <remap if="$(arg sim)" from="follow_joint_trajectory" to="arm_controller/follow_joint_trajectory"/>

        <!-- Remap follow_joint_trajectory -->

        <!-- Launch moveit -->

          <!-- the cylinder poses publisher node -->

  </group>


  <!-- for ros control to be used with scara robot -->
  <!--   <param name="/scara_robot_left/robot_description" textfile="$(find two_scara_collaboration)/urdf/scara_robot_left.urdf" />-->

<!-- spawn the red_box in gazebo -->
<!-- node name="spawn_red_box" pkg="gazebo_ros" type="spawn_model" args="-file $(find ur5_notebook)/urdf/red_box.urdf -urdf -model red_box"/ -->


</launch>

when I launch the above file the robots are launched but there is no execution of the 'ur5_mp.py'
I get the following error

Traceback (most recent call last):
  File "/home/murtaza/catkin_ws/src/ur5_notebook/ur5_mp.py", line 378, in <module>
    mp=ur5_mp()
  File "/home/murtaza/catkin_ws/src/ur5_notebook/ur5_mp.py", line 66, in __init__
    self.arm = moveit_commander.MoveGroupCommander(group_name)
  File "/opt/ros/melodic/lib/python2.7/dist-packages/moveit_commander/move_group.py", line 52, in __init__
    self._g = _moveit_move_group_interface.MoveGroupInterface(name, robot_description, ns)
RuntimeError: Unable to connect to move_group action server 'move_group' within allotted time (5s)
[INFO] [1568641657.813389, 0.000000]: Stopping the robot
Traceback (most recent call last):
  File "/opt/ros/melodic/lib/python2.7/dist-packages/rospy/core.py", line 572, in signal_shutdown
    h()
  File "/home/murtaza/catkin_ws/src/ur5_notebook/ur5_mp.py", line 157, in cleanup
    self.arm.stop()
AttributeError: ur5_mp instance has no attribute 'arm'
[robot1/ur5_mp-15] process has died [pid 35212, exit code 1, cmd /home/murtaza/catkin_ws/src/ur5_notebook/ur5_mp.py __name:=ur5_mp __log:=/home/murtaza/.ros/log/c6d316e8-d86b-11e9-a0db-000c29544a54/robot1-ur5_mp-15.log].
log file: /home/murtaza/.ros/log/c6d316e8-d86b-11e9-a0db-000c29544a54/robot1-ur5_mp-15*.log
[robot2/ur5_mp-25] process has died [pid 35239, exit code 1, cmd /home/murtaza/catkin_ws/src/ur5_notebook/ur5_mp.py __name:=ur5_mp __log:=/home/murtaza/.ros/log/c6d316e8-d86b-11e9-a0db-000c29544a54/robot2-ur5_mp-25.log].
log file: /home/murtaza/.ros/log/c6d316e8-d86b-11e9-a0db-000c29544a54/robot2-ur5_mp-25*.log

Here is the snippet of the result after execution

image

melodic

hi,is there someone work it out using melodic?

How can I adjust the speed of the red box and the arm?

Hi,lihuang3,I want to adjust the speed of the red box and the arm.I have tried modify the configuration file(joint_limits.yaml),the robot arm can grab the box,but then it fell off.I hope the box and arm can move fast,but now I don't know how to make it.Hope then you can give some suggestions,thanks.

why i cann't see the camera window when i roslaunch

The moveit software was deleted by mistake due to the installation of other software,After I reinstalled it, I found that gazebo could display scene objects, but the camera window did not appear and did not grab them. What's the matter? Did I delete the software that opened the window by mistake?

Looking forward to your reply

Error when roslaunch ur5_notebook initialize.launch

when i roslaunch ur5_notebook initialize.launch , termina output :
[ERROR] [1536718588.484370847, 2.176000000]: SpawnModel: Failure - entity format is invalid.
[ERROR] [1536718588.484485184, 2.176000000]: fail to connect with gazebo server

Does anyone know how to solve this problem?

ERROR: cannot launch node of type [ur5_notebook/blocks_spawner]: can't locate node [blocks_spawner] in package [ur5_notebook] ERROR: cannot launch node of type [ur5_notebook/blocks_poses_publisher]: can't locate node [blocks_poses_publisher] in package [ur5_notebook]

ERROR: cannot launch node of type [ur5_notebook/blocks_spawner]: can't locate node [blocks_spawner] in package [ur5_notebook] when I run roslaunch ur5_notebook.

ERROR: cannot launch node of type [ur5_notebook/blocks_poses_publisher]: can't locate node [blocks_poses_publisher] in package [ur5_notebook]

Does anyone know how to solve this kind of mistake, thank you

Noetic

Does anyone have the same for ros-noetic?

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.