Skip to content

Commit

Permalink
2.3.0
Browse files Browse the repository at this point in the history
- Conveyor add-on added
- Vision add-on added
- Fixes
- Examples added
  • Loading branch information
Wasta-Geek committed Jun 18, 2020
1 parent 8e74297 commit 9db9c3d
Show file tree
Hide file tree
Showing 197 changed files with 10,545 additions and 2,879 deletions.
2 changes: 1 addition & 1 deletion .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -8,4 +8,4 @@ tmp_code_to_execute/
*_test.py
/CMakeLists.txt
*.egg-info

*__pycache__
5 changes: 3 additions & 2 deletions niryo_one/package.xml
Original file line number Diff line number Diff line change
@@ -1,9 +1,10 @@
<package>
<name>niryo_one</name>
<version>2.2.0</version>
<version>2.3.0</version>
<description>Niryo One metapackage</description>
<author>Edouard Renard</author>
<maintainer email="[email protected]">Edouard Renard</maintainer>
<maintainer email="[email protected]">Rémi Lux</maintainer>
<maintainer email="[email protected]">Corentin Ducatez</maintainer>
<license>GPLv3</license>
<url type="website">https://niryo.com</url>
<url type="repository">https://github.com/niryorobotics/niryo_one_ros</url>
Expand Down
2 changes: 1 addition & 1 deletion niryo_one_bringup/config/niryo_one_driver.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ gpio_can_interrupt: 25
calibration_timeout: 40

#
# Read/Write/Check frequencies
# Read/Write/Check frequencies
# Those params have been chosen to get a good (connection performance + speed / CPU usage) ratio
#

Expand Down
15 changes: 12 additions & 3 deletions niryo_one_bringup/config/rpi_ros_processes.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -9,23 +9,32 @@ processes:
launch_on_startup: true
delay_before_start: 0.0
cmd: 'roslaunch niryo_one_bringup controllers.launch'
args:
args:
[]
dependencies:
[]
- name: 'robot_commander'
launch_on_startup: true
delay_before_start: 4.0 # Additional delay for Moveit to load controllers
cmd: 'roslaunch niryo_one_bringup robot_commander.launch'
args:
args:
[]
dependencies:
- controllers
- name: 'user_interface'
launch_on_startup: true
delay_before_start: 0.0
cmd: 'roslaunch niryo_one_bringup user_interface.launch'
args:
args:
[]
dependencies:
- controllers
- robot_commander
- name: 'vision_node'
launch_on_startup: true
delay_before_start: 5.0
cmd: 'roslaunch niryo_one_bringup vision.launch'
args:
[]
dependencies:
- controllers
Expand Down
7 changes: 7 additions & 0 deletions niryo_one_bringup/config/v2/niryo_one_motors.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,13 @@ can_required_motors: # Axis 1-3 of Niryo One (stepper 1 -> id 1, stepper 2 -> id
- 2 # Axis 2 enabled if not commented
- 3 # Axis 3 enabled if not commented

can_authorized_motors:
- 1 # Axis 1 enabled if not commented
- 2 # Axis 2 enabled if not commented
- 3 # Axis 3 enabled if not commented
- 6 # id for conveyor belt 1
- 7 # id for conveyor belt 2

dxl_required_motors: # axis 4, 5 and 6 of Niryo One.
# Edit only for debug purposes (ex : you want to test some motors separately and detached from the robot)
# --> Commented ids will make associated motor disable (and thus not trigger an error if not connected)
Expand Down
8 changes: 8 additions & 0 deletions niryo_one_bringup/config/v2/stepper_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,9 @@ stepper_1_gear_ratio: 6.0625
stepper_2_gear_ratio: 8.3125
stepper_3_gear_ratio: 7.875

stepper_6_gear_ratio: 5.0
stepper_7_gear_ratio: 5.0

stepper_1_offset_position: 3.05433
stepper_2_offset_position: 0.640187
stepper_3_offset_position: -1.397485
Expand All @@ -18,10 +21,15 @@ stepper_1_direction: -1.0
stepper_2_direction: -1.0
stepper_3_direction: 1.0

stepper_6_direction: -1.0
stepper_7_direction: -1.0

stepper_1_max_effort: 90
stepper_2_max_effort: 130
stepper_3_max_effort: 120

stepper_6_max_effort: 90
stepper_7_max_effort: 90

# Params still used in the driver code but motor 4 will be disabled
stepper_4_gear_ratio: 5.0
Expand Down
9 changes: 4 additions & 5 deletions niryo_one_bringup/launch/robot_commander.launch
Original file line number Diff line number Diff line change
Expand Up @@ -3,18 +3,18 @@

<!-- Moveit move_group -->
<include file="$(find niryo_one_moveit_config)/launch/move_group.launch" />

<!-- Disable Moveit! controller timeout -->
<param name="move_group/trajectory_execution/execution_duration_monitoring" value="false" />

<!-- Change start tolerance from 0.01 to 0.0 to avoid this error : "Invalid Trajectory: start point deviates from current robot state more than"-->
<!-- more info http://moveit.ros.org/moveit!/ros/2017/01/03/firstIndigoRelease.html -->
<param name="/move_group/trajectory_execution/allowed_start_tolerance" value="0.0" />

<!-- Change from 0.1 to 0.3 rad -->
<!-- Allows joints to be outside of min and max values when starting -->
<param name="/move_group/start_state_max_bounds_error" value="0.3" />

<!-- Robot commander -->
<node name="niryo_one_commander" pkg="niryo_one_commander" type="niryo_one_commander_node.py" output="screen" respawn="false">
<param name="reference_frame" type="string" value="world" />
Expand All @@ -30,4 +30,3 @@

</node>
</launch>

9 changes: 9 additions & 0 deletions niryo_one_bringup/launch/vision.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
<launch>
<node name="niryo_one_pose_converter" pkg="niryo_one_pose_converter" type="pose_converter.py" output="screen">
<param name="workspace_dir" type="string" value="~/niryo_one_workspaces/"/>
<param name="grip_dir" type="string" value="$(find niryo_one_pose_converter)/grips"/>
</node>
<node name="niryo_one_vision" pkg="niryo_one_camera" type="camera_publisher_and_services.py" output="screen">
<rosparam file="$(find niryo_one_camera)/config/video_server_setup.yaml"/>
</node>
</launch>
4 changes: 2 additions & 2 deletions niryo_one_bringup/package.xml
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
<?xml version="1.0"?>
<package>
<name>niryo_one_bringup</name>
<version>2.2.0</version>
<version>2.3.0</version>
<description>Provides roslaunch scripts to start Niryo One packages and ros params</description>
<author>Edouard Renard</author>
<maintainer email="e.renard@niryo.com">Edouard Renard</maintainer>
<maintainer email="r.lux@niryo.com">Rémi Lux</maintainer>
<license>GPLv3</license>

<buildtool_depend>catkin</buildtool_depend>
Expand Down
15 changes: 15 additions & 0 deletions niryo_one_camera/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
cmake_minimum_required(VERSION 2.8.3)
project(niryo_one_camera)

find_package(catkin REQUIRED COMPONENTS
rospy
std_msgs
)

catkin_python_setup()

catkin_package()

include_directories(
${catkin_INCLUDE_DIRS}
)
42 changes: 42 additions & 0 deletions niryo_one_camera/OPENCV_LICENSE
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
By downloading, copying, installing or using the software you agree to this license.
If you do not agree to this license, do not download, install,
copy or use the software.


License Agreement
For Open Source Computer Vision Library
(3-clause BSD License)

Copyright (C) 2000-2020, Intel Corporation, all rights reserved.
Copyright (C) 2009-2011, Willow Garage Inc., all rights reserved.
Copyright (C) 2009-2016, NVIDIA Corporation, all rights reserved.
Copyright (C) 2010-2013, Advanced Micro Devices, Inc., all rights reserved.
Copyright (C) 2015-2016, OpenCV Foundation, all rights reserved.
Copyright (C) 2015-2016, Itseez Inc., all rights reserved.
Copyright (C) 2019-2020, Xperience AI, all rights reserved.
Third party copyrights are property of their respective owners.

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 names of the copyright holders nor the names of the 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 copyright holders 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.
40 changes: 40 additions & 0 deletions niryo_one_camera/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
# Niryo One Vision
This package handles the image processing part of the Niryo One.
It's made from several publishers and services to ease the camera's use

## Setup
The setup happens in _niryo_one_camera/config/_. In this folder, you must have a
- _video_server_setup.yaml_ file which will contains several parameters has the frame rate use or the camera port.
- _XXXXXX.yaml_ file which represents camera intrinsic parameters. The name of the later should be mentionned
in the field **obj_calib_name** of the file setup file _video_server_setup.yaml_


## Launch
To launch the vision node, you can use the command :
`roslaunch niryo_one_bringup vision_node.launch`

Note that if you want to run it locally, you can use the following launch file :
```xml
<launch>
<node name="niryo_one_vision" pkg="niryo_one_camera" type="camera_publisher_and_services.py" output="screen">
<rosparam file="$(find niryo_one_camera)/config/video_server_setup_local.yaml"/>
</node>
</launch>
```

## Topic list

Publishers list
- _/niryo_one_vision/compressed_video_stream_ : Publish CompressedImage messages
each time a image is read and decoded. The actualization rate will vary according
to the frame rate and the subsampling rate

Services list
- _/niryo_one_vision/obj_detection_rel_ : Gives a relative position of a
specify object. Use ObjDetection srv
- _/niryo_one_vision/set_calibration_camera_ : Set new camera intrinsics object.
Use SetCalibrationCam srv
- _/niryo_one_vision/get_calibration_camera_ : Get infos about camera intrinsics parameters.
Use GetCalibrationCam srv
- _/niryo_one_vision/take_picture_ : Save the last image seen in a specified path. Use TakePicture srv
- _/niryo_one_vision/start_stop_video_streaming_ : Start and stop video streaming. Use SetBool from std_srvs
20 changes: 20 additions & 0 deletions niryo_one_camera/config/cam_intrinsics.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
mtx:
- 508.069
- 0.0
- 332.821
- 0.0
- 506.445
- 242.984
- 0.0
- 0.0
- 1.0

dist:
- -0.4146402
- 0.2407384
- 0.0
- 0.0
- -0.1040042

width_img: 640
height_img: 480
20 changes: 20 additions & 0 deletions niryo_one_camera/config/video_server_setup.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
# -- Editable settings
undistort_stream: false
frame_rate: 15 # 15, 25 or 30
subsampling: 5
camera_port: -1
calibration_grid_shape:
- 9
- 6

# For expert
obj_calib_name: "cam_intrinsics"
frame_size: # Available resolutions : 320x240, 352x288, 640x360, 640x480, 1280x720, 1920x1080
- 640 # width
- 480 # height

buffer_size: 5
display: false # Useful only on computer

stream_compression_quality: 65
debug_compression_quality: 75
32 changes: 32 additions & 0 deletions niryo_one_camera/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
<?xml version="1.0"?>
<package format="2">
<name>niryo_one_camera</name>
<version>2.3.0</version>
<description>Niryo vision package</description>
<author>Rémi Lux</author>
<author>Andreas Voigt</author>
<maintainer email="[email protected]">Rémi Lux</maintainer>

<license>GPLv3</license>

<build_depend>message_generation</build_depend>
<build_export_depend>message_generation</build_export_depend>
<buildtool_depend>catkin</buildtool_depend>
<build_depend>roscpp</build_depend>
<build_depend>rospy</build_depend>
<build_depend>sensor_msgs</build_depend>
<build_depend>std_msgs</build_depend>
<build_export_depend>roscpp</build_export_depend>
<build_export_depend>rospy</build_export_depend>
<build_export_depend>sensor_msgs</build_export_depend>
<build_export_depend>std_msgs</build_export_depend>
<exec_depend>roscpp</exec_depend>
<exec_depend>rospy</exec_depend>
<exec_depend>sensor_msgs</exec_depend>
<exec_depend>std_msgs</exec_depend>


<export>

</export>
</package>
Loading

0 comments on commit 9db9c3d

Please sign in to comment.